APM:Libraries
AP_Airspeed_MS5525.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 /*
18  backend driver for airspeed from I2C
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Param/AP_Param.h>
23 #include <AP_HAL/utility/OwnPtr.h>
24 #include <AP_HAL/I2CDevice.h>
25 #include <utility>
26 
27 #include "AP_Airspeed_Backend.h"
28 #include <AP_HAL/I2CDevice.h>
29 
31 {
32 public:
33  enum MS5525_ADDR {
36  MS5525_ADDR_AUTO = 255, // does not need to be 255, just needs to be out of the address array
37  };
38 
39  AP_Airspeed_MS5525(AP_Airspeed &frontend, uint8_t _instance, MS5525_ADDR address);
41 
42  // probe and initialise the sensor
43  bool init() override;
44 
45  // return the current differential_pressure in Pascal
46  bool get_differential_pressure(float &pressure) override;
47 
48  // return the current temperature in degrees C, if available
49  bool get_temperature(float &temperature) override;
50 
51 private:
52  void measure();
53  void collect();
54  void timer();
55  bool read_prom(void);
56  uint16_t crc4_prom(void);
57  int32_t read_adc();
58  void calculate();
59 
60  float pressure;
61  float temperature;
63  float pressure_sum;
64  uint32_t temp_count;
65  uint32_t press_count;
66 
68 
69  uint16_t prom[8];
70  uint8_t state;
71  int32_t D1;
72  int32_t D2;
73  uint32_t command_send_us;
75  uint8_t cmd_sent;
77 
79 };
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
bool get_temperature(float &temperature) override
A system for managing and storing variables that are of general interest to the system.
bool get_differential_pressure(float &pressure) override
AP_Airspeed_MS5525(AP_Airspeed &frontend, uint8_t _instance, MS5525_ADDR address)