CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/baro.cpp
Views: 1798
1
#include "AP_Periph.h"
2
3
#ifdef HAL_PERIPH_ENABLE_BARO
4
5
/*
6
barometer support
7
*/
8
9
#include <dronecan_msgs.h>
10
11
/*
12
update CAN baro
13
*/
14
void AP_Periph_FW::can_baro_update(void)
15
{
16
if (!periph.g.baro_enable) {
17
return;
18
}
19
baro.update();
20
if (last_baro_update_ms == baro.get_last_update()) {
21
return;
22
}
23
24
last_baro_update_ms = baro.get_last_update();
25
if (!baro.healthy()) {
26
// don't send any data
27
return;
28
}
29
const float press = baro.get_pressure();
30
const float temp = baro.get_temperature();
31
32
{
33
uavcan_equipment_air_data_StaticPressure pkt {};
34
pkt.static_pressure = press;
35
pkt.static_pressure_variance = 0; // should we make this a parameter?
36
37
uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_MAX_SIZE];
38
uint16_t total_size = uavcan_equipment_air_data_StaticPressure_encode(&pkt, buffer, !periph.canfdout());
39
40
canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_SIGNATURE,
41
UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_ID,
42
CANARD_TRANSFER_PRIORITY_LOW,
43
&buffer[0],
44
total_size);
45
}
46
47
{
48
uavcan_equipment_air_data_StaticTemperature pkt {};
49
pkt.static_temperature = C_TO_KELVIN(temp);
50
pkt.static_temperature_variance = 0; // should we make this a parameter?
51
52
uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_MAX_SIZE];
53
uint16_t total_size = uavcan_equipment_air_data_StaticTemperature_encode(&pkt, buffer, !periph.canfdout());
54
55
canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_SIGNATURE,
56
UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_ID,
57
CANARD_TRANSFER_PRIORITY_LOW,
58
&buffer[0],
59
total_size);
60
}
61
}
62
63
#endif // HAL_PERIPH_ENABLE_BARO
64
65