2015-12-01 12:07:15 -04:00
|
|
|
#pragma once
|
2011-11-05 22:11:25 -03:00
|
|
|
|
2015-12-01 12:07:15 -04:00
|
|
|
#include "AP_Baro_Backend.h"
|
2011-11-05 22:11:25 -03:00
|
|
|
|
2022-01-26 23:58:56 -04:00
|
|
|
#if AP_BARO_MS56XX_ENABLED
|
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-07-25 10:33:28 -03:00
|
|
|
#include <AP_HAL/Semaphores.h>
|
2016-01-04 09:59:19 -04:00
|
|
|
#include <AP_HAL/Device.h>
|
2013-01-03 14:06:22 -04:00
|
|
|
|
2016-11-24 20:59:14 -04:00
|
|
|
#ifndef HAL_BARO_MS5611_I2C_ADDR
|
|
|
|
#define HAL_BARO_MS5611_I2C_ADDR 0x77
|
|
|
|
#endif
|
|
|
|
|
2018-09-05 22:54:43 -03:00
|
|
|
#ifndef HAL_BARO_MS5611_I2C_ADDR2
|
|
|
|
#define HAL_BARO_MS5611_I2C_ADDR2 0x76
|
|
|
|
#endif
|
|
|
|
|
2018-08-22 21:42:06 -03:00
|
|
|
#ifndef HAL_BARO_MS5607_I2C_ADDR
|
|
|
|
#define HAL_BARO_MS5607_I2C_ADDR 0x77
|
|
|
|
#endif
|
|
|
|
|
2017-02-03 00:18:25 -04:00
|
|
|
#ifndef HAL_BARO_MS5837_I2C_ADDR
|
|
|
|
#define HAL_BARO_MS5837_I2C_ADDR 0x76
|
|
|
|
#endif
|
|
|
|
|
2018-08-22 21:42:06 -03:00
|
|
|
#ifndef HAL_BARO_MS5637_I2C_ADDR
|
|
|
|
#define HAL_BARO_MS5637_I2C_ADDR 0x76
|
|
|
|
#endif
|
|
|
|
|
2015-07-10 00:56:06 -03:00
|
|
|
class AP_Baro_MS56XX : public AP_Baro_Backend
|
2011-11-27 01:43:34 -04:00
|
|
|
{
|
2012-08-17 03:09:24 -03:00
|
|
|
public:
|
2018-11-07 08:11:28 -04:00
|
|
|
void update() override;
|
2013-01-03 14:06:22 -04:00
|
|
|
|
2016-11-24 20:59:14 -04:00
|
|
|
enum MS56XX_TYPE {
|
|
|
|
BARO_MS5611 = 0,
|
|
|
|
BARO_MS5607 = 1,
|
2017-02-03 00:18:25 -04:00
|
|
|
BARO_MS5637 = 2,
|
|
|
|
BARO_MS5837 = 3
|
2016-11-24 20:59:14 -04:00
|
|
|
};
|
|
|
|
|
2022-01-28 22:36:46 -04:00
|
|
|
static AP_Baro_Backend *probe_5611(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev) {
|
|
|
|
return probe(baro, std::move(dev), BARO_MS5611);
|
|
|
|
}
|
|
|
|
static AP_Baro_Backend *probe_5607(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev) {
|
|
|
|
return probe(baro, std::move(dev), BARO_MS5607);
|
|
|
|
}
|
|
|
|
static AP_Baro_Backend *probe_5637(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev) {
|
|
|
|
return probe(baro, std::move(dev), BARO_MS5637);
|
|
|
|
}
|
|
|
|
static AP_Baro_Backend *probe_5837(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev) {
|
|
|
|
return probe(baro, std::move(dev), BARO_MS5837);
|
|
|
|
}
|
|
|
|
|
|
|
|
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, enum MS56XX_TYPE ms56xx_type=BARO_MS5611);
|
2019-04-23 19:32:50 -03:00
|
|
|
|
2016-11-24 20:59:14 -04:00
|
|
|
private:
|
2022-01-28 22:36:46 -04:00
|
|
|
|
2016-07-25 10:33:28 -03:00
|
|
|
/*
|
|
|
|
* Update @accum and @count with the new sample in @val, taking into
|
|
|
|
* account a maximum number of samples given by @max_count; in case
|
|
|
|
* maximum number is reached, @accum and @count are updated appropriately
|
|
|
|
*/
|
|
|
|
static void _update_and_wrap_accumulator(uint32_t *accum, uint32_t val,
|
|
|
|
uint8_t *count, uint8_t max_count);
|
|
|
|
|
2016-11-24 20:59:14 -04:00
|
|
|
AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, enum MS56XX_TYPE ms56xx_type);
|
2018-01-01 20:33:08 -04:00
|
|
|
|
2016-11-24 20:59:14 -04:00
|
|
|
bool _init();
|
2015-11-26 10:56:10 -04:00
|
|
|
|
2016-11-24 20:59:14 -04:00
|
|
|
void _calculate_5611();
|
|
|
|
void _calculate_5607();
|
|
|
|
void _calculate_5637();
|
2017-02-03 00:18:25 -04:00
|
|
|
void _calculate_5837();
|
2016-11-24 20:59:14 -04:00
|
|
|
bool _read_prom_5611(uint16_t prom[8]);
|
|
|
|
bool _read_prom_5637(uint16_t prom[8]);
|
2016-01-04 09:59:19 -04:00
|
|
|
|
|
|
|
uint16_t _read_prom_word(uint8_t word);
|
|
|
|
uint32_t _read_adc();
|
|
|
|
|
2017-01-13 15:26:14 -04:00
|
|
|
void _timer();
|
2015-11-04 18:17:38 -04:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
2014-07-07 00:11:41 -03:00
|
|
|
|
2016-07-25 10:33:28 -03:00
|
|
|
/* Shared values between thread sampling the HW and main thread */
|
|
|
|
struct {
|
|
|
|
uint32_t s_D1;
|
|
|
|
uint32_t s_D2;
|
|
|
|
uint8_t d1_count;
|
|
|
|
uint8_t d2_count;
|
|
|
|
} _accum;
|
|
|
|
|
|
|
|
uint8_t _state;
|
2016-07-25 13:52:33 -03:00
|
|
|
uint8_t _instance;
|
2012-11-19 21:23:26 -04:00
|
|
|
|
2016-07-25 13:52:33 -03:00
|
|
|
/* Last compensated values from accumulated sample */
|
|
|
|
float _D1, _D2;
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
// Internal calibration registers
|
2016-07-25 13:52:33 -03:00
|
|
|
struct {
|
|
|
|
uint16_t c1, c2, c3, c4, c5, c6;
|
|
|
|
} _cal_reg;
|
2016-11-13 02:08:06 -04:00
|
|
|
|
|
|
|
bool _discard_next;
|
2015-07-10 00:56:06 -03:00
|
|
|
|
2016-11-24 20:59:14 -04:00
|
|
|
enum MS56XX_TYPE _ms56xx_type;
|
2015-09-28 15:31:12 -03:00
|
|
|
};
|
2022-01-26 23:58:56 -04:00
|
|
|
|
|
|
|
#endif // AP_BARO_MS56XX_ENABLED
|