Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_AUAV.h
4183 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
#include "AP_Airspeed_config.h"
18
19
#if AP_AIRSPEED_AUAV_ENABLED
20
21
/*
22
backend driver for airspeed from I2C
23
*/
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 AUAV_Pressure_sensor
32
{
33
public:
34
enum class Type {
35
Differential,
36
Absolute,
37
};
38
39
AUAV_Pressure_sensor(AP_HAL::I2CDevice *&_dev, Type _type);
40
41
// start a measurement
42
// Return true if successful
43
bool measure() WARN_IF_UNUSED;
44
45
enum class Status {
46
Normal, // Happy, valid reading
47
Busy, // Busy, try reading again later
48
Fault, // Something bad has happened
49
};
50
51
// read the values from the sensor
52
// Return status
53
// pressure corrected but not scaled to the correct units
54
// temperature in degrees centigrade
55
Status collect(float &PComp, float &temperature) WARN_IF_UNUSED;
56
57
// Read coefficients in stages
58
enum class CoefficientStage {
59
A_high,
60
A_low,
61
B_high,
62
B_low,
63
C_high,
64
C_low,
65
D_high,
66
D_low,
67
E_high,
68
E_low,
69
Done,
70
} stage;
71
72
// Read extended compensation coefficients from sensor
73
void read_coefficients();
74
75
// Read 4 bytes compensation coefficient
76
bool read_register(uint8_t cmd, uint16_t &result);
77
78
private:
79
AP_HAL::I2CDevice *&dev;
80
81
Type type;
82
83
// Extended compensation coefficients
84
// Theses are read from the sensor in read_coefficients
85
float LIN_A;
86
float LIN_B;
87
float LIN_C;
88
float LIN_D;
89
float Es;
90
float TC50H;
91
float TC50L;
92
93
// Step of reading coefficients, request must be made before read.
94
enum class CoefficientStep {
95
request,
96
read,
97
} coefficient_step;
98
99
};
100
101
class AP_Airspeed_AUAV : public AP_Airspeed_Backend
102
{
103
public:
104
AP_Airspeed_AUAV(AP_Airspeed &frontend, uint8_t _instance, const float _range_inH2O);
105
~AP_Airspeed_AUAV(void) {
106
delete _dev;
107
}
108
109
// probe and initialise the sensor
110
bool init() override;
111
112
// return the current differential_pressure in Pascal
113
bool get_differential_pressure(float &pressure) override;
114
115
// return the current temperature in degrees C, if available
116
bool get_temperature(float &temperature) override;
117
118
private:
119
bool probe(uint8_t bus, uint8_t address);
120
void _timer();
121
122
uint32_t last_sample_time_ms;
123
bool measurement_requested;
124
AP_HAL::I2CDevice *_dev;
125
126
AUAV_Pressure_sensor sensor { _dev, AUAV_Pressure_sensor::Type::Differential };
127
128
float pressure;
129
float temp_C;
130
const float range_inH2O;
131
};
132
133
#endif // AP_Airspeed_AUAV_ENABLED
134
135