Path: blob/master/libraries/AP_Baro/AP_Baro_MS5611.h
9782 views
#pragma once12#include "AP_Baro_Backend.h"34#if AP_BARO_MS56XX_ENABLED56#include <AP_HAL/AP_HAL.h>7#include <AP_HAL/Semaphores.h>8#include <AP_HAL/Device.h>910#ifndef HAL_BARO_MS5611_I2C_ADDR11#define HAL_BARO_MS5611_I2C_ADDR 0x7712#endif1314#ifndef HAL_BARO_MS5611_I2C_ADDR215#define HAL_BARO_MS5611_I2C_ADDR2 0x7616#endif1718#ifndef HAL_BARO_MS5607_I2C_ADDR19#define HAL_BARO_MS5607_I2C_ADDR 0x7720#endif2122#ifndef HAL_BARO_MS5837_I2C_ADDR23#define HAL_BARO_MS5837_I2C_ADDR 0x7624#endif2526#ifndef HAL_BARO_MS5637_I2C_ADDR27#define HAL_BARO_MS5637_I2C_ADDR 0x7628#endif2930#if AP_BARO_MS5837_ENABLED31// Determined in https://github.com/ArduPilot/ardupilot/pull/29122#issuecomment-287726911432#define MS5837_30BA_02BA_SELECTION_THRESHOLD 3700033#endif3435class AP_Baro_MS56XX : public AP_Baro_Backend36{37public:38void update() override;3940AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::Device &dev);4142protected:4344// convenience methods for derivative classes to call. Will free45// sensor if it can't init it.46static AP_Baro_Backend *_probe(AP_Baro &baro, AP_Baro_MS56XX *sensor);4748virtual bool _init();4950bool _read_prom_5611(uint16_t prom[8]);51bool _read_prom_5637(uint16_t prom[8]);5253virtual const char *name() const = 0;54virtual DevTypes devtype() const = 0;5556uint8_t _instance;5758/* Last compensated values from accumulated sample */59float _D1, _D2;6061// Internal calibration registers62struct {63uint16_t c1, c2, c3, c4, c5, c6;64} _cal_reg;6566private:6768static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);6970/*71* Update @accum and @count with the new sample in @val, taking into72* account a maximum number of samples given by @max_count; in case73* maximum number is reached, @accum and @count are updated appropriately74*/75static void _update_and_wrap_accumulator(uint32_t *accum, uint32_t val,76uint8_t *count, uint8_t max_count);7778uint16_t _read_prom_word(uint8_t word);79uint32_t _read_adc();8081void _timer();8283AP_HAL::Device *_dev;8485/* Shared values between thread sampling the HW and main thread */86struct {87uint32_t s_D1;88uint32_t s_D2;89uint8_t d1_count;90uint8_t d2_count;91} _accum;9293uint8_t _state;9495bool _discard_next;9697virtual bool _read_prom(uint16_t *prom) = 0;98virtual void _calculate() = 0;99};100101#if AP_BARO_MS5607_ENABLED102class AP_Baro_MS5607 : public AP_Baro_MS56XX103{104public:105using AP_Baro_MS56XX::AP_Baro_MS56XX;106static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);107protected:108const char *name() const override { return "MS5607"; }109bool _read_prom(uint16_t *prom) override { return _read_prom_5611(prom); }110DevTypes devtype() const override { return DEVTYPE_BARO_MS5607; }111void _calculate() override;112};113#endif // AP_BARO_MS5607_ENABLED114115#if AP_BARO_MS5611_ENABLED116class AP_Baro_MS5611 : public AP_Baro_MS56XX117{118public:119using AP_Baro_MS56XX::AP_Baro_MS56XX;120static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);121protected:122const char *name() const override { return "MS5611"; }123bool _read_prom(uint16_t *prom) override { return _read_prom_5611(prom); }124DevTypes devtype() const override { return DEVTYPE_BARO_MS5611; }125void _calculate() override;126};127#endif // AP_BARO_MS5611_ENABLED128129#if AP_BARO_MS5637_ENABLED130class AP_Baro_MS5637 : public AP_Baro_MS56XX131{132public:133using AP_Baro_MS56XX::AP_Baro_MS56XX;134static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);135protected:136const char *name() const override { return "MS5637"; }137bool _read_prom(uint16_t *prom) override { return _read_prom_5637(prom); }138DevTypes devtype() const override { return DEVTYPE_BARO_MS5637; }139void _calculate() override;140};141#endif // AP_BARO_MS5637_ENABLED142143#if AP_BARO_MS5837_ENABLED144class AP_Baro_MS5837 : public AP_Baro_MS56XX145{146public:147using AP_Baro_MS56XX::AP_Baro_MS56XX;148static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);149protected:150const char *name() const override { return "MS5837"; }151bool _read_prom(uint16_t *prom) override { return _read_prom_5637(prom); }152DevTypes devtype() const override;153bool _init() override;154void _calculate() override;155void _calculate_5837_02ba();156void _calculate_5837_30ba();157158DevTypes _subtype;159};160#endif // AP_BARO_MS5837_ENABLED161162#endif // AP_BARO_MS56XX_ENABLED163164165