25 #define BMP085_OVERSAMPLING_ULTRALOWPOWER 0 26 #define BMP085_OVERSAMPLING_STANDARD 1 27 #define BMP085_OVERSAMPLING_HIGHRES 2 28 #define BMP085_OVERSAMPLING_ULTRAHIGHRES 3 32 #define OVERSAMPLING BMP085_OVERSAMPLING_ULTRAHIGHRES 34 #define OVERSAMPLING BMP085_OVERSAMPLING_HIGHRES 39 , _dev(
std::move(dev))
50 if (!sensor || !sensor->
_init()) {
113 ac1 = ((int16_t)bb.buff[0] << 8) | bb.buff[1];
114 ac2 = ((int16_t)bb.buff[2] << 8) | bb.buff[3];
115 ac3 = ((int16_t)bb.buff[4] << 8) | bb.buff[5];
116 ac4 = ((int16_t)bb.buff[6] << 8) | bb.buff[7];
117 ac5 = ((int16_t)bb.buff[8] << 8) | bb.buff[9];
118 ac6 = ((int16_t)bb.buff[10]<< 8) | bb.buff[11];
119 b1 = ((int16_t)bb.buff[12] << 8) | bb.buff[13];
120 b2 = ((int16_t)bb.buff[14] << 8) | bb.buff[15];
121 mb = ((int16_t)bb.buff[16] << 8) | bb.buff[17];
122 mc = ((int16_t)bb.buff[18] << 8) | bb.buff[19];
123 md = ((int16_t)bb.buff[20] << 8) | bb.buff[21];
125 if ((
ac1==0 ||
ac1==-1) ||
128 (
ac4==0 ||
ac4==0xFFFF) ||
129 (
ac5==0 ||
ac5==0xFFFF) ||
130 (
ac6==0 ||
ac6==0xFFFF)) {
152 const uint8_t reg = 0xAA + (word << 1);
157 return (val[0] << 8) | val[1];
162 bool all_zero =
true;
163 for (uint8_t i = 0; i < 11; i++) {
233 | ((uint32_t)buf[1] << 8)
241 | ((uint32_t)buf[1] << 8)
262 int32_t _temp_sensor;
268 _temp_sensor = buf[0];
269 _temp_sensor = (_temp_sensor << 8) | buf[1];
277 int32_t x1, x2, x3, b3, b5, b6, p;
285 x2 = ((int32_t)
mc << 11) / (x1 +
md);
287 _temp = (b5 + 8) >> 4;
291 x1 = (
b2 * (b6 * b6 >> 12)) >> 11;
300 x2 = (
b1 * (b6 * b6 >> 12)) >> 16;
301 x3 = ((x1 + x2) + 2) >> 2;
302 b4 = (
ac4 * (uint32_t)(x3 + 32768)) >> 15;
304 p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2;
306 x1 = (p >> 8) * (p >> 8);
307 x1 = (x1 * 3038) >> 16;
308 x2 = (-7357 * p) >> 16;
309 p += ((x1 + x2 + 3791) >> 4);
333 uint32_t conversion_time_msec;
337 conversion_time_msec = 5;
340 conversion_time_msec = 8;
343 conversion_time_msec = 14;
346 conversion_time_msec = 26;
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
AP_HAL::DigitalSource * _eoc
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
virtual AP_HAL::Semaphore * get_semaphore()=0
uint16_t _read_prom_word(uint8_t word)
AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
uint32_t _last_press_read_command_time
uint32_t _last_temp_read_command_time
virtual void mode(uint8_t output)=0
AP_HAL::OwnPtr< AP_HAL::Device > _dev
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AverageIntegralFilter< int32_t, int32_t, 10 > _pressure_filter
static AP_HAL::OwnPtr< AP_HAL::Device > dev
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
virtual T apply(T sample) override
virtual bool set_speed(Speed speed)=0
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
bool pressure_ok(float press)
#define BMP085_OVERSAMPLING_STANDARD
void _cmd_read_pressure()
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
Common definitions and utility routines for the ArduPilot libraries.
bool _read_prom(uint16_t *prom)
#define BMP085_OVERSAMPLING_ULTRAHIGHRES
#define BMP085_OVERSAMPLING_ULTRALOWPOWER
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void panic(const char *errormsg,...) FMT_PRINTF(1
#define BMP085_OVERSAMPLING_HIGHRES
bool write_register(uint8_t reg, uint8_t val, bool checked=false)