APM:Libraries
AP_Baro_BMP085.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #include <AP_HAL/I2CDevice.h>
6 #include <Filter/Filter.h>
7 
8 #include "AP_Baro_Backend.h"
9 
10 #ifndef HAL_BARO_BMP085_I2C_ADDR
11 #define HAL_BARO_BMP085_I2C_ADDR (0x77)
12 #endif
13 
15 public:
17 
18  /* AP_Baro public interface: */
19  void update();
20 
22 
23 
24 private:
25  bool _init();
26 
27  void _cmd_read_pressure();
28  void _cmd_read_temp();
29  bool _read_pressure();
30  void _read_temp();
31  void _calculate();
32  bool _data_ready();
33 
34  void _timer(void);
35 
36  uint16_t _read_prom_word(uint8_t word);
37  bool _read_prom(uint16_t *prom);
38 
39 
42 
43  uint8_t _instance;
45 
46  // Boards with no EOC pin: use times instead
49 
50  // State machine
51  uint8_t _state;
52 
53  // Internal calibration registers
54  int16_t ac1, ac2, ac3, b1, b2, mb, mc, md;
55  uint16_t ac4, ac5, ac6;
56 
57  int32_t _raw_pressure;
58  int32_t _raw_temp;
59  int32_t _temp;
61 
62  uint8_t _vers;
63  uint8_t _type;
64 };
AP_HAL::DigitalSource * _eoc
uint16_t _read_prom_word(uint8_t word)
AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
uint32_t _last_press_read_command_time
uint32_t _last_temp_read_command_time
AP_HAL::OwnPtr< AP_HAL::Device > _dev
int32_t _raw_pressure
AverageIntegralFilter< int32_t, int32_t, 10 > _pressure_filter
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
static AP_Baro baro
Definition: ModuleTest.cpp:18
bool _read_prom(uint16_t *prom)