mirror of https://github.com/arendst/Tasmota.git
MS5837 functionality with BMP280 optional dependency (#22376)
* Finalized gain/integration adjustment trees * Fixed the bugs * works but polishing code * need to debug pressure in bmp * updated temp to change via setoption8 command from tasmota * sensor table working, value reporting working, need to update dependency on sensor duality * working * updated file name for ms5837 xsns file * final working with renamed for current updates (128->116) * resolved PR comments for extra spaces, xi2c_96 * removed extra spaces, added unit for inches across languages * added "Water depth" for languages * removed inches as a unit from language files * switched to centimeter units for SI consistency in Tasmota * all variables showing in console and table; need to adjust offsets * cm conversion properly reporting * Sensor116 in console calibrates the sensor's pressure_offset variable * removed pressure offset debugging lines * removed unecessary commented items from old code
This commit is contained in:
parent
19e15e21aa
commit
a35bb5a5c9
|
@ -1,6 +1,6 @@
|
|||
/**************************************************************************/
|
||||
/*!
|
||||
@file Adafruit_TSL2591.h
|
||||
/*!
|
||||
@file Adafruit_TSL2591.h
|
||||
@author KT0WN (adafruit.com)
|
||||
|
||||
This is a library for the Adafruit TSL2591 breakout board
|
||||
|
|
|
@ -0,0 +1,258 @@
|
|||
#include "MS5837.h"
|
||||
#include <Wire.h>
|
||||
|
||||
const uint8_t MS5837_ADDR = 0x76;
|
||||
const uint8_t MS5837_RESET = 0x1E;
|
||||
const uint8_t MS5837_ADC_READ = 0x00;
|
||||
const uint8_t MS5837_PROM_READ = 0xA0;
|
||||
const uint8_t MS5837_CONVERT_D1_8192 = 0x4A;
|
||||
const uint8_t MS5837_CONVERT_D2_8192 = 0x5A;
|
||||
|
||||
const float MS5837::Pa = 100.0f;
|
||||
const float MS5837::bar = 0.001f;
|
||||
const float MS5837::mbar = 1.0f;
|
||||
|
||||
const uint8_t MS5837::MS5837_30BA = 0;
|
||||
const uint8_t MS5837::MS5837_02BA = 1;
|
||||
const uint8_t MS5837::MS5837_UNRECOGNISED = 255;
|
||||
|
||||
const uint8_t MS5837_02BA01 = 0x00; // Sensor version: From MS5837_02BA datasheet Version PROM Word 0
|
||||
const uint8_t MS5837_02BA21 = 0x15; // Sensor version: From MS5837_02BA datasheet Version PROM Word 0
|
||||
const uint8_t MS5837_30BA26 = 0x1A; // Sensor version: From MS5837_30BA datasheet Version PROM Word 0
|
||||
|
||||
MS5837::MS5837() {
|
||||
fluidDensity = 1029;
|
||||
}
|
||||
|
||||
bool MS5837::begin(TwoWire &wirePort) {
|
||||
return (init(wirePort));
|
||||
}
|
||||
|
||||
bool MS5837::init(TwoWire &wirePort) {
|
||||
_i2cPort = &wirePort; //Grab which port the user wants us to use
|
||||
|
||||
// Reset the MS5837, per datasheet
|
||||
_i2cPort->beginTransmission(MS5837_ADDR);
|
||||
_i2cPort->write(MS5837_RESET);
|
||||
_i2cPort->endTransmission();
|
||||
|
||||
// Wait for reset to complete
|
||||
delay(10);
|
||||
|
||||
// Read calibration values and CRC
|
||||
for ( uint8_t i = 0 ; i < 7 ; i++ ) {
|
||||
_i2cPort->beginTransmission(MS5837_ADDR);
|
||||
_i2cPort->write(MS5837_PROM_READ+i*2);
|
||||
_i2cPort->endTransmission();
|
||||
|
||||
_i2cPort->requestFrom(MS5837_ADDR,2);
|
||||
C[i] = (_i2cPort->read() << 8) | _i2cPort->read();
|
||||
}
|
||||
|
||||
// Verify that data is correct with CRC
|
||||
uint8_t crcRead = C[0] >> 12;
|
||||
uint8_t crcCalculated = crc4(C);
|
||||
|
||||
if ( crcCalculated != crcRead ) {
|
||||
return false; // CRC fail
|
||||
}
|
||||
|
||||
uint8_t version = (C[0] >> 5) & 0x7F; // Extract the sensor version from PROM Word 0
|
||||
|
||||
// Set _model according to the sensor version
|
||||
if (version == MS5837_02BA01)
|
||||
{
|
||||
_model = MS5837_02BA;
|
||||
}
|
||||
else if (version == MS5837_02BA21)
|
||||
{
|
||||
_model = MS5837_02BA;
|
||||
}
|
||||
else if (version == MS5837_30BA26)
|
||||
{
|
||||
_model = MS5837_30BA;
|
||||
}
|
||||
else
|
||||
{
|
||||
_model = MS5837_UNRECOGNISED;
|
||||
}
|
||||
// The sensor has passed the CRC check, so we should return true even if
|
||||
// the sensor version is unrecognised.
|
||||
// (The MS5637 has the same address as the MS5837 and will also pass the CRC check)
|
||||
// (but will hopefully be unrecognised.)
|
||||
return true;
|
||||
}
|
||||
|
||||
void MS5837::setModel(uint8_t model) {
|
||||
_model = model;
|
||||
}
|
||||
|
||||
uint8_t MS5837::getModel() {
|
||||
return (_model);
|
||||
}
|
||||
|
||||
void MS5837::setFluidDensity(float density) {
|
||||
fluidDensity = density;
|
||||
}
|
||||
|
||||
void MS5837::read() {
|
||||
//Check that _i2cPort is not NULL (i.e. has the user forgoten to call .init or .begin?)
|
||||
if (_i2cPort == NULL)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
// Request D1 conversion
|
||||
_i2cPort->beginTransmission(MS5837_ADDR);
|
||||
_i2cPort->write(MS5837_CONVERT_D1_8192);
|
||||
_i2cPort->endTransmission();
|
||||
|
||||
delay(20); // Max conversion time per datasheet
|
||||
|
||||
_i2cPort->beginTransmission(MS5837_ADDR);
|
||||
_i2cPort->write(MS5837_ADC_READ);
|
||||
_i2cPort->endTransmission();
|
||||
|
||||
_i2cPort->requestFrom(MS5837_ADDR,3);
|
||||
D1_pres = 0;
|
||||
D1_pres = _i2cPort->read();
|
||||
D1_pres = (D1_pres << 8) | _i2cPort->read();
|
||||
D1_pres = (D1_pres << 8) | _i2cPort->read();
|
||||
|
||||
// Request D2 conversion
|
||||
_i2cPort->beginTransmission(MS5837_ADDR);
|
||||
_i2cPort->write(MS5837_CONVERT_D2_8192);
|
||||
_i2cPort->endTransmission();
|
||||
|
||||
delay(20); // Max conversion time per datasheet
|
||||
|
||||
_i2cPort->beginTransmission(MS5837_ADDR);
|
||||
_i2cPort->write(MS5837_ADC_READ);
|
||||
_i2cPort->endTransmission();
|
||||
|
||||
_i2cPort->requestFrom(MS5837_ADDR,3);
|
||||
D2_temp = 0;
|
||||
D2_temp = _i2cPort->read();
|
||||
D2_temp = (D2_temp << 8) | _i2cPort->read();
|
||||
D2_temp = (D2_temp << 8) | _i2cPort->read();
|
||||
|
||||
calculate();
|
||||
}
|
||||
|
||||
void MS5837::calculate() {
|
||||
// Given C1-C6 and D1, D2, calculated TEMP and P
|
||||
// Do conversion first and then second order temp compensation
|
||||
|
||||
int32_t dT = 0;
|
||||
int64_t SENS = 0;
|
||||
int64_t OFF = 0;
|
||||
int32_t SENSi = 0;
|
||||
int32_t OFFi = 0;
|
||||
int32_t Ti = 0;
|
||||
int64_t OFF2 = 0;
|
||||
int64_t SENS2 = 0;
|
||||
|
||||
// Terms called
|
||||
dT = D2_temp-uint32_t(C[5])*256l;
|
||||
if ( _model == MS5837_02BA ) {
|
||||
SENS = int64_t(C[1])*65536l+(int64_t(C[3])*dT)/128l;
|
||||
OFF = int64_t(C[2])*131072l+(int64_t(C[4])*dT)/64l;
|
||||
P = (D1_pres*SENS/(2097152l)-OFF)/(32768l);
|
||||
} else {
|
||||
SENS = int64_t(C[1])*32768l+(int64_t(C[3])*dT)/256l;
|
||||
OFF = int64_t(C[2])*65536l+(int64_t(C[4])*dT)/128l;
|
||||
P = (D1_pres*SENS/(2097152l)-OFF)/(8192l);
|
||||
}
|
||||
|
||||
// Temp conversion
|
||||
TEMP = 2000l+int64_t(dT)*C[6]/8388608LL;
|
||||
|
||||
//Second order compensation
|
||||
if ( _model == MS5837_02BA ) {
|
||||
if((TEMP/100)<20){ //Low temp
|
||||
Ti = (11*int64_t(dT)*int64_t(dT))/(34359738368LL);
|
||||
OFFi = (31*(TEMP-2000)*(TEMP-2000))/8;
|
||||
SENSi = (63*(TEMP-2000)*(TEMP-2000))/32;
|
||||
}
|
||||
} else {
|
||||
if((TEMP/100)<20){ //Low temp
|
||||
Ti = (3*int64_t(dT)*int64_t(dT))/(8589934592LL);
|
||||
OFFi = (3*(TEMP-2000)*(TEMP-2000))/2;
|
||||
SENSi = (5*(TEMP-2000)*(TEMP-2000))/8;
|
||||
if((TEMP/100)<-15){ //Very low temp
|
||||
OFFi = OFFi+7*(TEMP+1500l)*(TEMP+1500l);
|
||||
SENSi = SENSi+4*(TEMP+1500l)*(TEMP+1500l);
|
||||
}
|
||||
}
|
||||
else if((TEMP/100)>=20){ //High temp
|
||||
Ti = 2*(dT*dT)/(137438953472LL);
|
||||
OFFi = (1*(TEMP-2000)*(TEMP-2000))/16;
|
||||
SENSi = 0;
|
||||
}
|
||||
}
|
||||
|
||||
OFF2 = OFF-OFFi; //Calculate pressure and temp second order
|
||||
SENS2 = SENS-SENSi;
|
||||
|
||||
TEMP = (TEMP-Ti);
|
||||
|
||||
if ( _model == MS5837_02BA ) {
|
||||
P = (((D1_pres*SENS2)/2097152l-OFF2)/32768l);
|
||||
} else {
|
||||
P = (((D1_pres*SENS2)/2097152l-OFF2)/8192l);
|
||||
}
|
||||
}
|
||||
|
||||
float MS5837::pressure(float conversion) {
|
||||
if ( _model == MS5837_02BA ) {
|
||||
return P*conversion/100.0f;
|
||||
}
|
||||
else {
|
||||
return P*conversion/10.0f;
|
||||
}
|
||||
}
|
||||
|
||||
float MS5837::temperature() {
|
||||
return TEMP/100.0f;
|
||||
}
|
||||
|
||||
// The pressure sensor measures absolute pressure, so it will measure the atmospheric pressure + water pressure
|
||||
// We subtract the atmospheric pressure to calculate the depth with only the water pressure
|
||||
// The average atmospheric pressure of 101300 pascal is used for the calcuation, but atmospheric pressure varies
|
||||
// If the atmospheric pressure is not 101300 at the time of reading, the depth reported will be offset
|
||||
// In order to calculate the correct depth, the actual atmospheric pressure should be measured once in air, and
|
||||
// that value should subtracted for subsequent depth calculations.
|
||||
float MS5837::depth() {
|
||||
return (pressure(MS5837::Pa)-101300)/(fluidDensity*9.80665f);
|
||||
}
|
||||
|
||||
float MS5837::altitude() {
|
||||
return (1-pow((pressure()/1013.25f),.190284f))*145366.45f*.3048f;
|
||||
}
|
||||
|
||||
|
||||
uint8_t MS5837::crc4(uint16_t n_prom[]) {
|
||||
uint16_t n_rem = 0;
|
||||
|
||||
n_prom[0] = ((n_prom[0]) & 0x0FFF);
|
||||
n_prom[7] = 0;
|
||||
|
||||
for ( uint8_t i = 0 ; i < 16; i++ ) {
|
||||
if ( i%2 == 1 ) {
|
||||
n_rem ^= (uint16_t)((n_prom[i>>1]) & 0x00FF);
|
||||
} else {
|
||||
n_rem ^= (uint16_t)(n_prom[i>>1] >> 8);
|
||||
}
|
||||
for ( uint8_t n_bit = 8 ; n_bit > 0 ; n_bit-- ) {
|
||||
if ( n_rem & 0x8000 ) {
|
||||
n_rem = (n_rem << 1) ^ 0x3000;
|
||||
} else {
|
||||
n_rem = (n_rem << 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
n_rem = ((n_rem >> 12) & 0x000F);
|
||||
|
||||
return n_rem ^ 0x00;
|
||||
}
|
|
@ -0,0 +1,113 @@
|
|||
/* Blue Robotics Arduino MS5837-30BA Pressure/Temperature Sensor Library
|
||||
------------------------------------------------------------
|
||||
|
||||
Title: Blue Robotics Arduino MS5837-30BA Pressure/Temperature Sensor Library
|
||||
|
||||
Description: This library provides utilities to communicate with and to
|
||||
read data from the Measurement Specialties MS5837-30BA pressure/temperature
|
||||
sensor.
|
||||
|
||||
Authors: Rustom Jehangir, Blue Robotics Inc.
|
||||
Adam Šimko, Blue Robotics Inc.
|
||||
|
||||
-------------------------------
|
||||
The MIT License (MIT)
|
||||
|
||||
Copyright (c) 2015 Blue Robotics Inc.
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
of this software and associated documentation files (the "Software"), to deal
|
||||
in the Software without restriction, including without limitation the rights
|
||||
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in
|
||||
all copies or substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
THE SOFTWARE.
|
||||
-------------------------------*/
|
||||
|
||||
#ifndef MS5837_H_BLUEROBOTICS
|
||||
#define MS5837_H_BLUEROBOTICS
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <Wire.h>
|
||||
|
||||
class MS5837 {
|
||||
public:
|
||||
static const float Pa;
|
||||
static const float bar;
|
||||
static const float mbar;
|
||||
|
||||
static const uint8_t MS5837_30BA;
|
||||
static const uint8_t MS5837_02BA;
|
||||
static const uint8_t MS5837_UNRECOGNISED;
|
||||
|
||||
MS5837();
|
||||
|
||||
bool init(TwoWire &wirePort = Wire);
|
||||
bool begin(TwoWire &wirePort = Wire); // Calls init()
|
||||
|
||||
/** Set model of MS5837 sensor. Valid options are MS5837::MS5837_30BA (default)
|
||||
* and MS5837::MS5837_02BA.
|
||||
*/
|
||||
void setModel(uint8_t model);
|
||||
uint8_t getModel();
|
||||
|
||||
/** Provide the density of the working fluid in kg/m^3. Default is for
|
||||
* seawater. Should be 997 for freshwater.
|
||||
*/
|
||||
void setFluidDensity(float density);
|
||||
|
||||
/** The read from I2C takes up to 40 ms, so use sparingly is possible.
|
||||
*/
|
||||
void read();
|
||||
|
||||
/** Pressure returned in mbar or mbar*conversion rate.
|
||||
*/
|
||||
float pressure(float conversion = 1.0f);
|
||||
|
||||
/** Temperature returned in deg C.
|
||||
*/
|
||||
float temperature();
|
||||
|
||||
/** Depth returned in meters (valid for operation in incompressible
|
||||
* liquids only. Uses density that is set for fresh or seawater.
|
||||
*/
|
||||
float depth();
|
||||
|
||||
/** Altitude returned in meters (valid for operation in air only).
|
||||
*/
|
||||
float altitude();
|
||||
|
||||
uint8_t crc4(uint16_t n_prom[]);
|
||||
|
||||
private:
|
||||
|
||||
//This stores the requested i2c port
|
||||
TwoWire * _i2cPort;
|
||||
|
||||
uint16_t C[8];
|
||||
uint32_t D1_pres, D2_temp;
|
||||
int32_t TEMP;
|
||||
int32_t P;
|
||||
uint8_t _model;
|
||||
|
||||
float fluidDensity;
|
||||
|
||||
/** Performs calculations per the sensor data sheet for conversion and
|
||||
* second order compensation.
|
||||
*/
|
||||
void calculate();
|
||||
|
||||
//uint8_t crc4(uint16_t n_prom[]);
|
||||
};
|
||||
|
||||
#endif
|
|
@ -219,6 +219,7 @@
|
|||
#define D_JSON_VERSION "Version"
|
||||
#define D_JSON_VOLTAGE "Voltage"
|
||||
#define D_JSON_VOLUME "Volume"
|
||||
#define D_JSON_WATER_DEPTH "Water Depth"
|
||||
#define D_JSON_WEIGHT "Weight"
|
||||
#define D_JSON_WIFI "Wifi"
|
||||
#define D_JSON_WIFI_MODE "Mode"
|
||||
|
@ -1001,6 +1002,7 @@ const char HTTP_SNS_MILLILITERS[] PROGMEM = "{s}%s " D_VOLUME "{
|
|||
const char HTTP_SNS_GAS[] PROGMEM = "{s}%s " D_GAS "{m}%d " D_UNIT_PERCENT "LEL{e}";
|
||||
const char HTTP_SNS_SOC[] PROGMEM = "{s}%s " D_SOC "{m}%d " D_UNIT_PERCENT "{e}";
|
||||
const char HTTP_SNS_SOH[] PROGMEM = "{s}%s " D_SOH "{m}%d " D_UNIT_PERCENT "{e}";
|
||||
const char HTTP_SNS_WATER_DEPTH[] PROGMEM = "{s}%s " D_WATER_DEPTH "{m}%s " D_UNIT_CENTIMETER "{e}";
|
||||
|
||||
const char HTTP_SNS_STANDARD_CONCENTRATION[] PROGMEM = "{s}%s " D_STANDARD_CONCENTRATION " %s " D_UNIT_MICROMETER "{m}%d " D_UNIT_MICROGRAM_PER_CUBIC_METER "{e}";
|
||||
const char HTTP_SNS_ENVIRONMENTAL_CONCENTRATION[] PROGMEM = "{s}%s " D_ENVIRONMENTAL_CONCENTRATION " %s " D_UNIT_MICROMETER "{m}%d " D_UNIT_MICROGRAM_PER_CUBIC_METER "{e}";
|
||||
|
|
|
@ -173,6 +173,7 @@
|
|||
//#define USE_MAX17043 // [I2cDriver83] Enable MAX17043 fuel-gauge systems Lipo batteries sensor (I2C address 0x36) (+0k9 code)
|
||||
//#define USE_AMSX915 // [I2CDriver86] Enable AMS5915/AMS6915 pressure/temperature sensor (+1k2 code)
|
||||
//#define USE_SPL06_007 // [I2cDriver87] Enable SPL06_007 pressure and temperature sensor (I2C addresses 0x76) (+2k5 code)
|
||||
//#define USE_MS5837
|
||||
|
||||
//#define USE_RTC_CHIPS // Enable RTC chip support and NTP server - Select only one
|
||||
// #define USE_DS3231 // [I2cDriver26] Enable DS3231 RTC (I2C address 0x68) (+1k2 code)
|
||||
|
|
|
@ -450,6 +450,7 @@
|
|||
//#define USE_LUXV30B // [I2CDriver70] Enable RFRobot SEN0390 LuxV30b ambient light sensor (I2C address 0x4A) (+0k5 code)
|
||||
//#define USE_PMSA003I // [I2cDriver78] Enable PMSA003I Air Quality Sensor (I2C address 0x12) (+1k8 code)
|
||||
//#define USE_GDK101 // [I2cDriver79] Enable GDK101 sensor (I2C addresses 0x18 - 0x1B) (+1k2 code)
|
||||
// #define USE_MS5837
|
||||
|
||||
//#define USE_RTC_CHIPS // Enable RTC chip support and NTP server - Select only one
|
||||
// #define USE_DS3231 // [I2cDriver26] Enable DS3231 RTC (I2C address 0x68) (+1k2 code)
|
||||
|
@ -692,6 +693,7 @@
|
|||
//#define USE_LUXV30B // [I2CDriver70] Enable RFRobot SEN0390 LuxV30b ambient light sensor (I2C address 0x4A) (+0k5 code)
|
||||
//#define USE_PMSA003I // [I2cDriver78] Enable PMSA003I Air Quality Sensor (I2C address 0x12) (+1k8 code)
|
||||
//#define USE_GDK101 // [I2cDriver79] Enable GDK101 sensor (I2C addresses 0x18 - 0x1B) (+1k2 code)
|
||||
// #define USE_MS5837
|
||||
|
||||
//#define USE_RTC_CHIPS // Enable RTC chip support and NTP server - Select only one
|
||||
// #define USE_DS3231 // [I2cDriver26] Enable DS3231 RTC (I2C address 0x68) (+1k2 code)
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Webbediener"
|
||||
#define D_SOC "Laai kondisie"
|
||||
#define D_SOH "Laai vermoeë"
|
||||
#define D_WATER_DEPTH "Water diepte"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "WAARSKUWING Hierdie weergawe ondersteun nie aanhoudende instellings nie"
|
||||
|
@ -1289,7 +1290,7 @@
|
|||
#define D_MOVING_ENERGY_T "Moving target"
|
||||
#define D_STATIC_ENERGY_T "Static target"
|
||||
#define D_LD2410_PIN_STATE "Output pin state"
|
||||
#define D_LD2410_LIGHT "Light sensor"
|
||||
#define D_LD2410_LIGHT "Light sensor"
|
||||
|
||||
// xsns_115_wooliis.ino
|
||||
#define D_IMPORT "Import"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Уеб сървър"
|
||||
#define D_SOC "Съснояние на зареждане"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Дълбочина на водата"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "ПРЕДУПРЕЖДЕНИЕ Тази версия не поддържа постоянни настройки"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Servidor Web"
|
||||
#define D_SOC "Estat de canvi"
|
||||
#define D_SOH "Estat de salut"
|
||||
#define D_WATER_DEPTH "Profunditat de l'aigua"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "Avís : Aquesta versió no suporta configuració persistent"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Web Server"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Hloubka vody"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "UPOZORNĚNÍ Tato verze nepodporuje trvalé nastavení"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Webserver"
|
||||
#define D_SOC "Ladestatus"
|
||||
#define D_SOH "Gesundheitsstatus"
|
||||
#define D_WATER_DEPTH "Wassertiefe"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "ACHTUNG: Diese Version unterstützt keine persistenten Einstellungen"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Διακομιστής Web"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Βάθος νερού"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "ΠΡΟΕΙΔΟΠΟΙΗΣΗ Αυτή η έκδοση δεν αποθηκεύει τις ρυθμίσεις"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Web Server"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Water Depth"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "WARNING This version does not support persistent settings"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Servidor Web"
|
||||
#define D_SOC "Estado de Carga"
|
||||
#define D_SOH "Estado de Salud"
|
||||
#define D_WATER_DEPTH "Profundidad del agua"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "Cuidado, esta versión no guarda los cambios"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Serveur web"
|
||||
#define D_SOC "État de la Charge"
|
||||
#define D_SOH "État de Santé"
|
||||
#define D_WATER_DEPTH "Profondeur de l’eau"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "ATTENTION Cette version ne gère pas les réglages persistants"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Webserver"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Charge"
|
||||
#define D_WATER_DEPTH "Vattendjup"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "WARSKOGING Dizze ferzje bewarret gjin ynstellings"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Web שרת"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "עומק המים"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "אזהרה גרסה זו אינה תומכת בהגדרות קבועות"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Webszerver"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Vízmélység"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "VIGYÁZZ! Ez a verzió nem támogat tartós beállításokat"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Server web"
|
||||
#define D_SOC "Stato di carica"
|
||||
#define D_SOH "State di salute"
|
||||
#define D_WATER_DEPTH "Profondità dell'acqua"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "ATTENZIONE Questa versione non supporta il salvataggio delle impostazioni"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "웹 서버"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "수심"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "경고: 이 버전은 영구 설정을 지원하지 않습니다"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Webserver"
|
||||
#define D_SOC "Laadtoestand"
|
||||
#define D_SOH "Gezondheid"
|
||||
#define D_WATER_DEPTH "Diepte van het water"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "WAARSCHUWING Deze versie bewaart geen instellingen"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Serwer Web"
|
||||
#define D_SOC "Stan naładowania"
|
||||
#define D_SOH "Kondycja"
|
||||
#define D_WATER_DEPTH "Głębokość wody"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "UWAGA Ta wersja nie obsługuje zapisu ustawień"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Servidor WEB"
|
||||
#define D_SOC "Estado de Carga"
|
||||
#define D_SOH "Estado de Saúde"
|
||||
#define D_WATER_DEPTH "Profundidade da água"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "AVISO: esta versão não supporta configurações persistentes"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Servidor WEB"
|
||||
#define D_SOC "Estado de Carga"
|
||||
#define D_SOH "Estado de Saúde"
|
||||
#define D_WATER_DEPTH "Profundidade da água"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "AVISO esta versão não supporta configurações persistentes"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Server Web"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Adâncimea apei"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "ATENȚIE Această versiune nu suportă setări permanente"
|
||||
|
|
|
@ -216,6 +216,7 @@
|
|||
#define D_WEB_SERVER "Веб-сервер"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Глубина воды"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "ПРЕДУПРЕЖДЕНИЕ Эта версия не поддерживает персистентные настройки"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Web Server"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Hĺbka vody"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "UPOZORNENIE Táto verzia nepodporuje trvalé nastavenia"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Webbserver"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Vattendjup"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "VARNING Denna version supporterar inte beständiga inställningar"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Web Sunucusu"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Su derinliği"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "UYARI Bu versiyon ayarların kalıcı olarak kaydedilmesine olanak sağlamıyor"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Web сервер"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Глибина води"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "ПОПЕРЕДЖЕННЯ! Ця версія не підтримує збереження налаштувань"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Máy chủ Web"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "Độ sâu nước"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "Cảnh báo phiên bản này không hỗ trợ các cài đặt vĩnh viễn"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "Web服务器"
|
||||
#define D_SOC "充电状态"
|
||||
#define D_SOH "充电健康"
|
||||
#define D_WATER_DEPTH "水深"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "警告:精简固件不支持持久保存设置"
|
||||
|
|
|
@ -215,6 +215,7 @@
|
|||
#define D_WEB_SERVER "網頁伺服器"
|
||||
#define D_SOC "State of Charge"
|
||||
#define D_SOH "State of Health"
|
||||
#define D_WATER_DEPTH "水深"
|
||||
|
||||
// tasmota.ino
|
||||
#define D_WARNING_MINIMAL_VERSION "警告,這個版本並不支援將設定永久的儲存!"
|
||||
|
|
|
@ -750,6 +750,7 @@
|
|||
// #define USE_AMSX915 // [I2CDriver86] Enable AMS5915/AMS6915 pressure/temperature sensor (+1k2 code)
|
||||
// #define USE_SPL06_007 // [I2cDriver87] Enable SPL06_007 pressure and temperature sensor (I2C addresses 0x76) (+2k5 code)
|
||||
// #define USE_QMP6988 // [I2cDriver88] Enable QMP6988 pressure and temperature sensor (I2C address 0x56 or 0x70) (+2k9 code)
|
||||
// #define USE_MS5837
|
||||
|
||||
// #define USE_RTC_CHIPS // Enable RTC chip support and NTP server - Select only one
|
||||
// #define USE_DS3231 // [I2cDriver26] Enable DS3231 RTC - used by Ulanzi TC001 (I2C address 0x68) (+1k2 code)
|
||||
|
|
|
@ -16,7 +16,6 @@
|
|||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifdef USE_I2C
|
||||
#ifdef USE_BMP
|
||||
/*********************************************************************************************\
|
||||
|
|
|
@ -0,0 +1,148 @@
|
|||
/*
|
||||
xsns_116_ms5837.ino - BlueRobotics MS5837 pressure and temperature sensor support for Tasmota
|
||||
|
||||
Copyright (C) 2022 Theo Arends, Stefan Tibus
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifdef USE_I2C
|
||||
#ifdef USE_MS5837
|
||||
|
||||
#define MS5837_ADDR 0x76
|
||||
|
||||
#define XSNS_116 116
|
||||
#define XI2C_91 91 // See I2CDEVICES.md
|
||||
/*********************************************************************************************\
|
||||
* BlueRobotics Pressure Sensor
|
||||
*
|
||||
* This driver supports the following sensors:
|
||||
* - BlueRobotics MS5837
|
||||
\*********************************************************************************************/
|
||||
|
||||
#include <Wire.h>
|
||||
#include <MS5837.h>
|
||||
|
||||
MS5837 sensor_ms5837;
|
||||
|
||||
uint8_t ms5837Start = 0;
|
||||
float pressure_offset = 2.85f;
|
||||
|
||||
/********************************************************************************************/
|
||||
|
||||
void MS5837init(void) {
|
||||
|
||||
if (I2cSetDevice(0x76)) {
|
||||
TwoWire& myWire = I2cGetWire();
|
||||
|
||||
if(sensor_ms5837.init(myWire)) {
|
||||
sensor_ms5837.setModel(sensor_ms5837.MS5837_02BA);
|
||||
sensor_ms5837.setFluidDensity(997); // kg/m^3 (freshwater, 1029 for seawater)
|
||||
ms5837Start = 1;
|
||||
I2cSetActiveFound(MS5837_ADDR, "MS5837");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_WEBSERVER
|
||||
const char name_str[] PROGMEM = "MS5837";
|
||||
#endif // USE_WEBSERVER
|
||||
|
||||
void MS5837Show(bool json) {
|
||||
float ms5837Temp;
|
||||
float ms5837Pres;
|
||||
float pressure_delta;
|
||||
float cm_water;
|
||||
char temperature_str[8];
|
||||
char pressure_str[8];
|
||||
char cmWater_str[8];
|
||||
|
||||
if (I2cEnabled(XI2C_91)) {
|
||||
sensor_ms5837.read();
|
||||
ms5837Temp = ConvertTemp(sensor_ms5837.temperature());
|
||||
ms5837Pres = ConvertPressure(sensor_ms5837.pressure() + pressure_offset);
|
||||
ext_snprintf_P(temperature_str, sizeof(temperature_str), PSTR("%1_f"), &ms5837Temp);
|
||||
ext_snprintf_P(pressure_str, sizeof(pressure_str), PSTR("%1_f"), &ms5837Pres);
|
||||
if (json) {
|
||||
ResponseAppend_P(PSTR(",\"MS5837\":{\"" D_JSON_TEMPERATURE "\":%s,\"" D_JSON_PRESSURE "\":%s"), temperature_str, pressure_str);
|
||||
}
|
||||
if (I2cEnabled(XI2C_10)) {
|
||||
pressure_delta = (sensor_ms5837.pressure() + pressure_offset) - bmp_sensors[0].bmp_pressure;
|
||||
cm_water = pressure_delta*0.401463078662f*2.54f; // changes from inches to cm after read using 2.54cm/in conversion
|
||||
ext_snprintf_P(cmWater_str, sizeof(cmWater_str), PSTR("%1_f"), &cm_water);
|
||||
if (json) {
|
||||
ResponseAppend_P(PSTR(",\"" D_JSON_WATER_DEPTH "\":%s"),cmWater_str);
|
||||
}
|
||||
}
|
||||
if (json) {
|
||||
ResponseAppend_P(PSTR("}"));
|
||||
|
||||
#ifdef USE_WEBSERVER
|
||||
} else {
|
||||
WSContentSend_PD(HTTP_SNS_F_TEMP, name_str, Settings->flag2.temperature_resolution, &ms5837Temp, TempUnit());
|
||||
WSContentSend_PD(HTTP_SNS_PRESSURE, name_str, pressure_str, PressureUnit().c_str());
|
||||
if (I2cEnabled(XI2C_10)) {
|
||||
WSContentSend_PD(HTTP_SNS_WATER_DEPTH, name_str, &cmWater_str);
|
||||
}
|
||||
#endif // USE_WEBSERVER
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool ms5837CommandSensor() {
|
||||
bool serviced = true;
|
||||
switch (XdrvMailbox.payload) {
|
||||
case 0:
|
||||
MS5837Show(0);
|
||||
pressure_offset = bmp_sensors[0].bmp_pressure - sensor_ms5837.pressure();
|
||||
break;
|
||||
}
|
||||
return serviced;
|
||||
}
|
||||
|
||||
/*********************************************************************************************\
|
||||
* Interface
|
||||
\*********************************************************************************************/
|
||||
|
||||
bool Xsns116(uint32_t function) {
|
||||
if (!I2cEnabled(XI2C_91)) { return false; }
|
||||
|
||||
bool result = false;
|
||||
//I2cScan();
|
||||
|
||||
if (FUNC_INIT == function) {
|
||||
MS5837init();
|
||||
}
|
||||
else if (ms5837Start) {
|
||||
switch (function) {
|
||||
case FUNC_COMMAND_SENSOR:
|
||||
if (XSNS_116 == XdrvMailbox.index) {
|
||||
result = ms5837CommandSensor();
|
||||
}
|
||||
break;
|
||||
case FUNC_JSON_APPEND:
|
||||
MS5837Show(1);
|
||||
break;
|
||||
#ifdef USE_WEBSERVER
|
||||
case FUNC_WEB_SENSOR:
|
||||
MS5837Show(0);
|
||||
break;
|
||||
#endif // USE_WEBSERVER
|
||||
}
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
#endif // USE_MS5837
|
||||
#endif // USE_I2C
|
Loading…
Reference in New Issue