Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_AUAV.cpp
4182 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
#include "AP_Baro_AUAV.h"
16
17
#if AP_BARO_AUAV_ENABLED
18
19
#include <utility>
20
21
extern const AP_HAL::HAL &hal;
22
23
AP_Baro_AUAV::AP_Baro_AUAV(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> _dev)
24
: AP_Baro_Backend(baro)
25
, dev(std::move(_dev))
26
{
27
i2c_dev = (AP_HAL::I2CDevice*)dev.get();
28
}
29
30
AP_Baro_Backend *AP_Baro_AUAV::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> _dev)
31
{
32
if (!_dev) {
33
return nullptr;
34
}
35
36
AP_Baro_AUAV *sensor = NEW_NOTHROW AP_Baro_AUAV(baro, std::move(_dev));
37
if (!sensor || !sensor->init()) {
38
delete sensor;
39
return nullptr;
40
}
41
return sensor;
42
}
43
44
bool AP_Baro_AUAV::init()
45
{
46
if (!i2c_dev) {
47
return false;
48
}
49
50
{
51
// Take semaphore for i2c functions
52
WITH_SEMAPHORE(i2c_dev->get_semaphore());
53
i2c_dev->set_retries(10);
54
55
// Request a measurement
56
if (!sensor.measure()) {
57
return false;
58
}
59
hal.scheduler->delay(40);
60
61
// Test read and discard result as the compensation coefficients are not configured
62
float PComp, temperature;
63
if (sensor.collect(PComp, temperature) != AUAV_Pressure_sensor::Status::Normal) {
64
return false;
65
}
66
}
67
68
// Register sensor and set dev-id
69
instance = _frontend.register_sensor();
70
i2c_dev->set_device_type(DEVTYPE_BARO_AUAV);
71
set_bus_id(instance, i2c_dev->get_bus_id());
72
73
i2c_dev->register_periodic_callback(40000,
74
FUNCTOR_BIND_MEMBER(&AP_Baro_AUAV::timer, void));
75
76
return true;
77
}
78
79
// accumulate a new sensor reading
80
void AP_Baro_AUAV::timer(void)
81
{
82
if (sensor.stage != AUAV_Pressure_sensor::CoefficientStage::Done) {
83
sensor.read_coefficients();
84
return;
85
}
86
87
if (measurement_requested) {
88
// Read in result of last measurement
89
float Pcomp, temp_C;
90
switch (sensor.collect(Pcomp, temp_C)) {
91
case AUAV_Pressure_sensor::Status::Normal: {
92
// Convert to correct units
93
const float pressure_mbar = 250 + (1.25 * ((Pcomp-1677722)/16777216.0) * 1000.0);
94
{
95
WITH_SEMAPHORE(_sem);
96
pressure_sum += pressure_mbar * 100;
97
temperature_sum += temp_C;
98
count++;
99
}
100
break;
101
}
102
case AUAV_Pressure_sensor::Status::Busy:
103
// Don't request a new measurement
104
return;
105
106
case AUAV_Pressure_sensor::Status::Fault:
107
break;
108
}
109
}
110
111
// Request a new measurement
112
measurement_requested = sensor.measure();
113
}
114
115
// transfer data to the frontend
116
void AP_Baro_AUAV::update(void)
117
{
118
if (count == 0) {
119
return;
120
}
121
122
WITH_SEMAPHORE(_sem);
123
124
_copy_to_frontend(instance, pressure_sum/count, temperature_sum/count);
125
126
pressure_sum = 0;
127
temperature_sum = 0;
128
count = 0;
129
}
130
131
#endif // AP_BARO_AUAV_ENABLED
132
133