Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp
9623 views
1
#include "AP_Airspeed_MSP.h"
2
3
#if AP_AIRSPEED_MSP_ENABLED
4
5
AP_Airspeed_MSP::AP_Airspeed_MSP(AP_Airspeed &_frontend, uint8_t _instance, uint8_t _msp_instance) :
6
AP_Airspeed_Backend(_frontend, _instance),
7
msp_instance(_msp_instance)
8
{
9
set_bus_id(AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_MSP,0,msp_instance,0));
10
}
11
12
// return the current differential_pressure in Pascal
13
bool AP_Airspeed_MSP::get_differential_pressure(float &pressure)
14
{
15
WITH_SEMAPHORE(sem);
16
if (press_count == 0) {
17
return false;
18
}
19
pressure = sum_pressure/press_count;
20
press_count = 0;
21
sum_pressure = 0;
22
return true;
23
}
24
25
// get last temperature
26
bool AP_Airspeed_MSP::get_temperature(float &temperature)
27
{
28
WITH_SEMAPHORE(sem);
29
if (temp_count == 0) {
30
return false;
31
}
32
temperature = sum_temp/temp_count;
33
temp_count = 0;
34
sum_temp = 0;
35
return true;
36
}
37
38
void AP_Airspeed_MSP::handle_msp(const MSP::msp_airspeed_data_message_t &pkt)
39
{
40
if (pkt.instance != msp_instance) {
41
// not for us
42
return;
43
}
44
WITH_SEMAPHORE(sem);
45
46
sum_pressure += pkt.pressure;
47
press_count++;
48
if (press_count > 100) {
49
// prevent overflow
50
sum_pressure /= 2;
51
press_count /= 2;
52
}
53
54
if (pkt.temp == INT16_MIN) {
55
// invalid temperature
56
return;
57
}
58
59
sum_temp += pkt.temp*0.01;
60
temp_count++;
61
if (temp_count > 100) {
62
// prevent overflow
63
sum_temp /= 2;
64
temp_count /= 2;
65
}
66
67
}
68
69
#endif // AP_AIRSPEED_MSP_ENABLED
70
71