Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_MS5525.h
9882 views
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_Airspeed_config.h"
22
23
#if AP_AIRSPEED_MS5525_ENABLED
24
25
#include <AP_HAL/AP_HAL.h>
26
#include <AP_HAL/I2CDevice.h>
27
#include <utility>
28
29
#include "AP_Airspeed_Backend.h"
30
31
class AP_Airspeed_MS5525 : public AP_Airspeed_Backend
32
{
33
public:
34
enum MS5525_ADDR {
35
MS5525_ADDR_1 = 0,
36
MS5525_ADDR_2 = 1,
37
MS5525_ADDR_AUTO = 255, // does not need to be 255, just needs to be out of the address array
38
};
39
40
AP_Airspeed_MS5525(AP_Airspeed &frontend, uint8_t _instance, MS5525_ADDR address);
41
~AP_Airspeed_MS5525(void) {
42
delete dev;
43
}
44
45
// probe and initialise the sensor
46
bool init() override;
47
48
// return the current differential_pressure in Pascal
49
bool get_differential_pressure(float &pressure) override;
50
51
// return the current temperature in degrees C, if available
52
bool get_temperature(float &temperature) override;
53
54
private:
55
void measure();
56
void collect();
57
void timer();
58
bool read_prom(void);
59
uint16_t crc4_prom(void);
60
int32_t read_adc();
61
void calculate();
62
63
float pressure;
64
float temperature;
65
float temperature_sum;
66
float pressure_sum;
67
uint32_t temp_count;
68
uint32_t press_count;
69
70
uint32_t last_sample_time_ms;
71
72
uint16_t prom[8];
73
uint8_t state;
74
int32_t D1;
75
int32_t D2;
76
uint32_t command_send_us;
77
bool ignore_next;
78
uint8_t cmd_sent;
79
MS5525_ADDR _address;
80
81
AP_HAL::I2CDevice *dev;
82
};
83
84
#endif // AP_AIRSPEED_MS5525_ENABLED
85
86