APM:Libraries
AP_Baro_MS5611.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_Baro_Backend.h"
4 
5 #include <AP_HAL/AP_HAL.h>
6 #include <AP_HAL/Semaphores.h>
7 #include <AP_HAL/Device.h>
8 
9 #ifndef HAL_BARO_MS5611_I2C_ADDR
10 #define HAL_BARO_MS5611_I2C_ADDR 0x77
11 #endif
12 
13 #ifndef HAL_BARO_MS5837_I2C_ADDR
14 #define HAL_BARO_MS5837_I2C_ADDR 0x76
15 #endif
16 
18 {
19 public:
20  void update();
21 
22  enum MS56XX_TYPE {
27  };
28 
30 
31 private:
32  /*
33  * Update @accum and @count with the new sample in @val, taking into
34  * account a maximum number of samples given by @max_count; in case
35  * maximum number is reached, @accum and @count are updated appropriately
36  */
37  static void _update_and_wrap_accumulator(uint32_t *accum, uint32_t val,
38  uint8_t *count, uint8_t max_count);
39 
41 
42  bool _init();
43 
44  void _calculate_5611();
45  void _calculate_5607();
46  void _calculate_5637();
47  void _calculate_5837();
48  bool _read_prom_5611(uint16_t prom[8]);
49  bool _read_prom_5637(uint16_t prom[8]);
50 
51  uint16_t _read_prom_word(uint8_t word);
52  uint32_t _read_adc();
53 
54  void _timer();
55 
57 
58  /* Shared values between thread sampling the HW and main thread */
59  struct {
60  uint32_t s_D1;
61  uint32_t s_D2;
62  uint8_t d1_count;
63  uint8_t d2_count;
64  } _accum;
65 
66  uint8_t _state;
67  uint8_t _instance;
68 
69  /* Last compensated values from accumulated sample */
70  float _D1, _D2;
71 
72  // Internal calibration registers
73  struct {
74  uint16_t c1, c2, c3, c4, c5, c6;
75  } _cal_reg;
76 
78 
80 };
static void _update_and_wrap_accumulator(uint32_t *accum, uint32_t val, uint8_t *count, uint8_t max_count)
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum MS56XX_TYPE ms56xx_type=BARO_MS5611)
struct AP_Baro_MS56XX::@11 _cal_reg
uint16_t _read_prom_word(uint8_t word)
struct AP_Baro_MS56XX::@10 _accum
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
static AP_Baro baro
Definition: ModuleTest.cpp:18
AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum MS56XX_TYPE ms56xx_type)
bool _read_prom_5611(uint16_t prom[8])
AP_HAL::OwnPtr< AP_HAL::Device > _dev
enum MS56XX_TYPE _ms56xx_type
uint32_t _read_adc()
bool _read_prom_5637(uint16_t prom[8])