├── ms5837 ├── __init__.py └── ms5837.py ├── setup.py ├── ms5837.meta ├── test-ms5837.py ├── LICENSE ├── report-ms5837.py ├── example.py └── README.md /ms5837/__init__.py: -------------------------------------------------------------------------------- 1 | from .ms5837 import * 2 | -------------------------------------------------------------------------------- /setup.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | from distutils.core import setup 4 | 5 | 6 | setup( 7 | name='ms5837', 8 | version='1.0', 9 | description='Interfaces with MS5837-30BA and MS5837-02BA waterproof ' 10 | 'pressure and temperature sensors', 11 | author='Blue Robotics', 12 | url='https://github.com/bluerobotics/ms5837-python', 13 | packages=['ms5837'], 14 | install_requires=['smbus2'], 15 | ) 16 | -------------------------------------------------------------------------------- /ms5837.meta: -------------------------------------------------------------------------------- 1 | { 2 | "0": { 3 | "llType": "error", 4 | "columns": [ 5 | { 6 | "llabel": "error message", 7 | "dtype": "str" 8 | } 9 | ] 10 | }, 11 | "1": { 12 | "llType": "data", 13 | "columns": [ 14 | { 15 | "llabel": "pressure", 16 | "units": "mbar", 17 | "dtype": "float" 18 | }, 19 | { 20 | "llabel": "temperature", 21 | "units": "degC", 22 | "dtype": "float" 23 | } 24 | ] 25 | } 26 | } 27 | -------------------------------------------------------------------------------- /test-ms5837.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python3 2 | 3 | from ms5837 import MS5837_02BA, MS5837_30BA 4 | from llog import LLogWriter 5 | 6 | device = 'ms5837' 7 | parser = LLogWriter.create_default_parser(__file__, device) 8 | parser.add_argument('--bar02', action='store_true', 9 | help='run test for Bar02 02BA model (default is Bar30 30BA model)') 10 | parser.add_argument('--bus', action='store', type=int, required=True) 11 | args = parser.parse_args() 12 | 13 | 14 | with llog.LLogWriter(args.meta, args.output) as log: 15 | MS5837 = MS5837_02BA if args.bar02 else MS5837_30BA 16 | ms = MS5837(args.bus) 17 | ms.init() 18 | 19 | def data_getter(): 20 | ms.read() 21 | return f"{ms.pressure()} {ms.temperature()}" 22 | 23 | log.log_data_loop(data_getter, parser_args=args) 24 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2017 Blue Robotics 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /report-ms5837.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python3 2 | 3 | import matplotlib.pyplot as plt 4 | 5 | DEVICE = 'ms5837' 6 | 7 | def generate_figures(log): 8 | footer = f'{DEVICE} test report' 9 | 10 | f, spec = log.figure(height_ratios=[1,1], suptitle=f'{DEVICE} data', footer=footer) 11 | """ TODO: uncomment once rom and config are available from test-ms5837.py 12 | plt.subplot(spec[0,0]) 13 | log.rom.T.ttable(rl=True) 14 | plt.subplot(spec[0,1]) 15 | log.config.T.ttable(rl=True) 16 | """ 17 | 18 | plt.subplot(spec[1,:]) 19 | log.data.pressure.pplot(log.data.temperature) 20 | 21 | if __name__ == '__main__': 22 | from llog import LLogReader 23 | from matplotlib.backends.backend_pdf import PdfPages 24 | 25 | parser = LLogReader.create_default_parser(__file__, DEVICE) 26 | args = parser.parse_args() 27 | 28 | log = LLogReader(args.input, args.meta) 29 | 30 | generate_figures(log) 31 | 32 | if args.output: 33 | # todo check if it exists! 34 | with PdfPages(args.output) as pdf: 35 | for n in plt.get_fignums(): 36 | pdf.savefig(n) 37 | 38 | if args.show: 39 | plt.show() 40 | -------------------------------------------------------------------------------- /example.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python 2 | import ms5837 3 | import time 4 | 5 | sensor = ms5837.MS5837_30BA() # Default I2C bus is 1 (Raspberry Pi 3) 6 | #sensor = ms5837.MS5837_30BA(0) # Specify I2C bus 7 | #sensor = ms5837.MS5837_02BA() 8 | #sensor = ms5837.MS5837_02BA(0) 9 | #sensor = ms5837.MS5837(model=ms5837.MS5837_MODEL_30BA, bus=0) # Specify model and bus 10 | 11 | # We must initialize the sensor before reading it 12 | if not sensor.init(): 13 | print("Sensor could not be initialized") 14 | exit(1) 15 | 16 | # We have to read values from sensor to update pressure and temperature 17 | if not sensor.read(): 18 | print("Sensor read failed!") 19 | exit(1) 20 | 21 | print(("Pressure: %.2f atm %.2f Torr %.2f psi") % ( 22 | sensor.pressure(ms5837.UNITS_atm), 23 | sensor.pressure(ms5837.UNITS_Torr), 24 | sensor.pressure(ms5837.UNITS_psi))) 25 | 26 | print(("Temperature: %.2f C %.2f F %.2f K") % ( 27 | sensor.temperature(ms5837.UNITS_Centigrade), 28 | sensor.temperature(ms5837.UNITS_Farenheit), 29 | sensor.temperature(ms5837.UNITS_Kelvin))) 30 | 31 | freshwaterDepth = sensor.depth() # default is freshwater 32 | sensor.setFluidDensity(ms5837.DENSITY_SALTWATER) 33 | saltwaterDepth = sensor.depth() # No nead to read() again 34 | sensor.setFluidDensity(1000) # kg/m^3 35 | print(("Depth: %.3f m (freshwater) %.3f m (saltwater)") % (freshwaterDepth, saltwaterDepth)) 36 | 37 | # fluidDensity doesn't matter for altitude() (always MSL air density) 38 | print(("MSL Relative Altitude: %.2f m") % sensor.altitude()) # relative to Mean Sea Level pressure in air 39 | 40 | time.sleep(5) 41 | 42 | # Spew readings 43 | while True: 44 | if sensor.read(): 45 | print(("P: %0.1f mbar %0.3f psi\tT: %0.2f C %0.2f F") % ( 46 | sensor.pressure(), # Default is mbar (no arguments) 47 | sensor.pressure(ms5837.UNITS_psi), # Request psi 48 | sensor.temperature(), # Default is degrees C (no arguments) 49 | sensor.temperature(ms5837.UNITS_Farenheit))) # Request Farenheit 50 | else: 51 | print("Sensor read failed!") 52 | exit(1) 53 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ms5837-python 2 | 3 | A python module to interface with MS5837-30BA and MS5837-02BA waterproof pressure and temperature sensors. Tested on Raspberry Pi 3 with Raspbian. 4 | 5 | # Installation 6 | 7 | The python SMBus library must be installed. 8 | 9 | sudo apt-get install python-smbus2 10 | 11 | Download this repository by clicking on the download button in this webpage, or using git: 12 | 13 | ```sh 14 | git clone https://github.com/bluerobotics/ms5837-python 15 | ``` 16 | 17 | If you would like to try the example, move to the directory where you downloaded the repository, and run `python example.py`. To use the library, copy the `ms5837.py` file to your project/program directory and use this import statement in your program: `import ms5837`. 18 | 19 | ### Raspberry Pi 20 | 21 | If you are using a Raspberry Pi, the i2c interface must be enabled. Run `sudo raspi-config`, and choose to enable the i2c interface in the `interfacing options`. 22 | 23 | # Usage 24 | 25 | import ms5837 26 | 27 | ms5837 provides a generic MS5837 class for use with different models 28 | 29 | MS5837(model=ms5837.MODEL_30BA, bus=1) 30 | 31 | These model-specific classes inherit from MS5837 and don't have any unique members 32 | 33 | MS5837_30BA(bus=1) 34 | MS5837_02BA(bus=1) 35 | 36 | An MS5837 object can be constructed by specifiying the model and the bus 37 | 38 | sensor = ms5837.MS5837() # Use defaults (MS5837-30BA device on I2C bus 1) 39 | sensor = ms5837.MS5837(ms5837.MODEL_02BA, 0) # Specify MS5837-02BA device on I2C bus 0 40 | 41 | Or by creating a model-specific object 42 | 43 | sensor = ms5837.MS5837_30BA() # Use default I2C bus (1) 44 | sensor = ms5837.MS5837_30BA(0) # Specify I2C bus 0 45 | 46 | ### init() 47 | 48 | Initialize the sensor. This needs to be called before using any other methods. 49 | 50 | sensor.init() 51 | 52 | Returns true if the sensor was successfully initialized, false otherwise. 53 | 54 | ### read(oversampling=OSR_8192) 55 | 56 | Read the sensor and update the pressure and temperature. The sensor will be read with the supplied oversampling setting. Greater oversampling increases resolution, but takes longer and increases current consumption. 57 | 58 | sensor.read(ms5837.OSR_256) 59 | 60 | Valid arguments are: 61 | 62 | ms5837.OSR_256 63 | ms5837.OSR_512 64 | ms5837.OSR_1024 65 | ms5837.OSR_2048 66 | ms5837.OSR_4096 67 | ms5837.OSR_8192 68 | 69 | Returns True if read was successful, False otherwise. 70 | 71 | ### setFluidDensity(density) 72 | 73 | Sets the density in (kg/m^3) of the fluid for depth measurements. The default fluid density is ms5837.DENISTY_FRESHWATER. 74 | 75 | sensor.setFluidDensity(1000) # Set fluid density to 1000 kg/m^3 76 | sensor.setFluidDensity(ms5837.DENSITY_SALTWATER) # Use predefined saltwater density 77 | 78 | Some convenient constants are: 79 | 80 | ms5837.DENSITY_FRESHWATER = 997 81 | ms5837.DENSITY_SALTWATER = 1029 82 | 83 | ### pressure(conversion=UNITS_mbar) 84 | 85 | Get the most recent pressure measurement. 86 | 87 | sensor.pressure() # Get pressure in default units (millibar) 88 | sensor.pressure(ms5837.UNITS_atm) # Get pressure in atmospheres 89 | sensor.pressure(ms5837.UNITS_kPa) # Get pressure in kilopascal 90 | 91 | Some convenient constants are: 92 | 93 | ms5837.UNITS_Pa = 100.0 94 | ms5837.UNITS_hPa = 1.0 95 | ms5837.UNITS_kPa = 0.1 96 | ms5837.UNITS_mbar = 1.0 97 | ms5837.UNITS_bar = 0.001 98 | ms5837.UNITS_atm = 0.000986923 99 | ms5837.UNITS_Torr = 0.750062 100 | ms5837.UNITS_psi = 0.014503773773022 101 | 102 | Returns the most recent pressure in millibar * conversion. Call read() to update. 103 | 104 | ### temperature(conversion=UNITS_Centigrade) 105 | 106 | Get the most recent temperature measurement. 107 | 108 | sensor.temperature() # Get temperature in default units (Centigrade) 109 | sensor.temperature(ms5837.UNITS_Farenheit) # Get temperature in Farenheit 110 | 111 | Valid arguments are: 112 | 113 | ms5837.UNITS_Centigrade 114 | ms5837.UNITS_Farenheit 115 | ms5837.UNITS_Kelvin 116 | 117 | Returns the most recent temperature in the requested units, or temperature in degrees Centigrade if invalid units specified. Call read() to update. 118 | 119 | ### depth() 120 | 121 | Get the most recent depth measurement in meters. 122 | 123 | sensor.depth() 124 | 125 | Returns the most recent depth in meters using the fluid density (kg/m^3) configured by setFluidDensity(). Call read() to update. 126 | 127 | ### altitude() 128 | 129 | Get the most recent altitude measurement relative to Mean Sea Level pressure in meters. 130 | 131 | sensor.altitude() 132 | 133 | Returns the most recent altitude in meters relative to MSL pressure using the density of air at MSL. Call read() to update. 134 | 135 | -------------------------------------------------------------------------------- /ms5837/ms5837.py: -------------------------------------------------------------------------------- 1 | try: 2 | import smbus2 as smbus 3 | except: 4 | print('Try sudo apt-get install python-smbus2') 5 | 6 | from time import sleep 7 | 8 | # Models 9 | MODEL_02BA = 0 10 | MODEL_30BA = 1 11 | MODEL_UNKNOWN = 255 12 | 13 | # context: https://github.com/ArduPilot/ardupilot/pull/29122#issuecomment-2877269114 14 | MS5837_02BA_MAX_SENSITIVITY = 49000; 15 | MS5837_02BA_30BA_SEPARATION = 37000; 16 | MS5837_30BA_MIN_SENSITIVITY = 26000; 17 | 18 | # Oversampling options 19 | OSR_256 = 0 20 | OSR_512 = 1 21 | OSR_1024 = 2 22 | OSR_2048 = 3 23 | OSR_4096 = 4 24 | OSR_8192 = 5 25 | 26 | # kg/m^3 convenience 27 | DENSITY_FRESHWATER = 997 28 | DENSITY_SALTWATER = 1029 29 | 30 | # Conversion factors (from native unit, mbar) 31 | UNITS_Pa = 100.0 32 | UNITS_hPa = 1.0 33 | UNITS_kPa = 0.1 34 | UNITS_mbar = 1.0 35 | UNITS_bar = 0.001 36 | UNITS_atm = 0.000986923 37 | UNITS_Torr = 0.750062 38 | UNITS_psi = 0.014503773773022 39 | 40 | # Valid units 41 | UNITS_Centigrade = 1 42 | UNITS_Farenheit = 2 43 | UNITS_Kelvin = 3 44 | 45 | 46 | class MS5837(object): 47 | 48 | # Registers 49 | _MS5837_ADDR = 0x76 50 | _MS5837_RESET = 0x1E 51 | _MS5837_ADC_READ = 0x00 52 | _MS5837_PROM_READ = 0xA0 53 | _MS5837_CONVERT_D1_256 = 0x40 54 | _MS5837_CONVERT_D2_256 = 0x50 55 | 56 | def __init__(self, model=MODEL_UNKNOWN, bus=1): 57 | self._model = model 58 | 59 | try: 60 | self._bus = smbus.SMBus(bus) 61 | except: 62 | print("Bus %d is not available."%bus) 63 | print("Available busses are listed as /dev/i2c*") 64 | self._bus = None 65 | 66 | self._fluidDensity = DENSITY_FRESHWATER 67 | self._pressure = 0 68 | self._temperature = 0 69 | self._D1 = 0 70 | self._D2 = 0 71 | 72 | def init(self): 73 | if self._bus is None: 74 | "No bus!" 75 | return False 76 | 77 | self._bus.write_byte(self._MS5837_ADDR, self._MS5837_RESET) 78 | 79 | # Wait for reset to complete 80 | sleep(0.01) 81 | 82 | self._C = [] 83 | 84 | # Read calibration values and CRC 85 | for i in range(7): 86 | c = self._bus.read_word_data(self._MS5837_ADDR, self._MS5837_PROM_READ + 2*i) 87 | c = ((c & 0xFF) << 8) | (c >> 8) # SMBus is little-endian for word transfers, we need to swap MSB and LSB 88 | self._C.append(c) 89 | 90 | crc = (self._C[0] & 0xF000) >> 12 91 | if crc != self._crc4(self._C): 92 | print("PROM read error, CRC failed!") 93 | return False 94 | 95 | if self._model == MODEL_UNKNOWN: 96 | self.auto_detect_model() 97 | 98 | return True 99 | 100 | def auto_detect_model(self): 101 | """ Automatically detect sensor variant, with a heuristic threshold. 102 | 103 | Details in https://github.com/ArduPilot/ardupilot/pull/29122#issuecomment-2877269114x 104 | 105 | TODO: include detection of product version / package type, from PROM Word 0, per 106 | https://github.com/ArduPilot/ardupilot/pull/29122#pullrequestreview-2837597764 107 | """ 108 | pressure_sensitivity = self._C[1] 109 | if MS5837_30BA_MIN_SENSITIVITY <= pressure_sensitivity <= MS5837_02BA_30BA_SEPARATION: 110 | self._model = MODEL_30BA 111 | elif MS5837_02BA_30BA_SEPARATION < pressure_sensitivity <= MS5837_02BA_MAX_SENSITIVITY: 112 | self._model = MODEL_02BA 113 | else: 114 | self._model = MODEL_UNKNOWN 115 | 116 | def read(self, oversampling=OSR_8192): 117 | if self._bus is None: 118 | print("No bus!") 119 | return False 120 | 121 | if oversampling < OSR_256 or oversampling > OSR_8192: 122 | print("Invalid oversampling option!") 123 | return False 124 | 125 | # Request D1 conversion (pressure) 126 | self._bus.write_byte(self._MS5837_ADDR, self._MS5837_CONVERT_D1_256 + 2*oversampling) 127 | 128 | # Maximum conversion time increases linearly with oversampling 129 | # max time (seconds) ~= 2.2e-6(x) where x = OSR = (2^8, 2^9, ..., 2^13) 130 | # We use 2.5e-6 for some overhead 131 | sleep(2.5e-6 * 2**(8+oversampling)) 132 | 133 | d = self._bus.read_i2c_block_data(self._MS5837_ADDR, self._MS5837_ADC_READ, 3) 134 | self._D1 = d[0] << 16 | d[1] << 8 | d[2] 135 | 136 | # Request D2 conversion (temperature) 137 | self._bus.write_byte(self._MS5837_ADDR, self._MS5837_CONVERT_D2_256 + 2*oversampling) 138 | 139 | # As above 140 | sleep(2.5e-6 * 2**(8+oversampling)) 141 | 142 | d = self._bus.read_i2c_block_data(self._MS5837_ADDR, self._MS5837_ADC_READ, 3) 143 | self._D2 = d[0] << 16 | d[1] << 8 | d[2] 144 | 145 | # Calculate compensated pressure and temperature 146 | # using raw ADC values and internal calibration 147 | self._calculate() 148 | 149 | return True 150 | 151 | def setFluidDensity(self, denisty): 152 | self._fluidDensity = denisty 153 | 154 | # Pressure in requested units 155 | # mbar * conversion 156 | def pressure(self, conversion=UNITS_mbar): 157 | return self._pressure * conversion 158 | 159 | # Temperature in requested units 160 | # default degrees C 161 | def temperature(self, conversion=UNITS_Centigrade): 162 | degC = self._temperature / 100.0 163 | if conversion == UNITS_Farenheit: 164 | return (9.0/5.0)*degC + 32 165 | elif conversion == UNITS_Kelvin: 166 | return degC + 273 167 | return degC 168 | 169 | # Depth relative to MSL pressure in given fluid density 170 | def depth(self): 171 | return (self.pressure(UNITS_Pa)-101300)/(self._fluidDensity*9.80665) 172 | 173 | # Altitude relative to MSL pressure 174 | def altitude(self): 175 | return (1-pow((self.pressure()/1013.25),.190284))*145366.45*.3048 176 | 177 | # Cribbed from datasheet 178 | def _calculate(self): 179 | OFFi = 0 180 | SENSi = 0 181 | Ti = 0 182 | 183 | dT = self._D2-self._C[5]*256 184 | if self._model == MODEL_02BA: 185 | SENS = self._C[1]*65536+(self._C[3]*dT)/128 186 | OFF = self._C[2]*131072+(self._C[4]*dT)/64 187 | self._pressure = (self._D1*SENS/(2097152)-OFF)/(32768) 188 | elif self._model == MODEL_30BA: 189 | SENS = self._C[1]*32768+(self._C[3]*dT)/256 190 | OFF = self._C[2]*65536+(self._C[4]*dT)/128 191 | self._pressure = (self._D1*SENS/(2097152)-OFF)/(8192) 192 | else: 193 | raise NotImplementedError("Cannot calculate pressure for unknown model type!") 194 | 195 | self._temperature = 2000+dT*self._C[6]/8388608 196 | 197 | # Second order compensation 198 | if self._model == MODEL_02BA: 199 | if (self._temperature/100) < 20: # Low temp 200 | Ti = (11*dT*dT)/(34359738368) 201 | OFFi = (31*(self._temperature-2000)*(self._temperature-2000))/8 202 | SENSi = (63*(self._temperature-2000)*(self._temperature-2000))/32 203 | 204 | else: 205 | if (self._temperature/100) < 20: # Low temp 206 | Ti = (3*dT*dT)/(8589934592) 207 | OFFi = (3*(self._temperature-2000)*(self._temperature-2000))/2 208 | SENSi = (5*(self._temperature-2000)*(self._temperature-2000))/8 209 | if (self._temperature/100) < -15: # Very low temp 210 | OFFi = OFFi+7*(self._temperature+1500)*(self._temperature+1500) 211 | SENSi = SENSi+4*(self._temperature+1500)*(self._temperature+1500) 212 | elif (self._temperature/100) >= 20: # High temp 213 | Ti = 2*(dT*dT)/(137438953472) 214 | OFFi = (1*(self._temperature-2000)*(self._temperature-2000))/16 215 | SENSi = 0 216 | 217 | OFF2 = OFF-OFFi 218 | SENS2 = SENS-SENSi 219 | 220 | if self._model == MODEL_02BA: 221 | self._temperature = (self._temperature-Ti) 222 | self._pressure = (((self._D1*SENS2)/2097152-OFF2)/32768)/100.0 223 | else: 224 | self._temperature = (self._temperature-Ti) 225 | self._pressure = (((self._D1*SENS2)/2097152-OFF2)/8192)/10.0 226 | 227 | # Cribbed from datasheet 228 | def _crc4(self, n_prom): 229 | n_rem = 0 230 | 231 | n_prom[0] = ((n_prom[0]) & 0x0FFF) 232 | n_prom.append(0) 233 | 234 | for i in range(16): 235 | if i%2 == 1: 236 | n_rem ^= ((n_prom[i>>1]) & 0x00FF) 237 | else: 238 | n_rem ^= (n_prom[i>>1] >> 8) 239 | 240 | for n_bit in range(8,0,-1): 241 | if n_rem & 0x8000: 242 | n_rem = (n_rem << 1) ^ 0x3000 243 | else: 244 | n_rem = (n_rem << 1) 245 | 246 | n_rem = ((n_rem >> 12) & 0x000F) 247 | 248 | self.n_prom = n_prom 249 | self.n_rem = n_rem 250 | 251 | return n_rem ^ 0x00 252 | 253 | class MS5837_30BA(MS5837): 254 | def __init__(self, bus=1): 255 | MS5837.__init__(self, MODEL_30BA, bus) 256 | 257 | class MS5837_02BA(MS5837): 258 | def __init__(self, bus=1): 259 | MS5837.__init__(self, MODEL_02BA, bus) 260 | --------------------------------------------------------------------------------