QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleTemperatureFactGroup.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4VehicleTemperatureFactGroup::VehicleTemperatureFactGroup(QObject *parent)
5 : FactGroup(1000, QStringLiteral(":/json/Vehicle/TemperatureFact.json"), parent)
6{
7 _addFact(&_temperature1Fact);
8 _addFact(&_temperature2Fact);
9 _addFact(&_temperature3Fact);
10
11 _temperature1Fact.setRawValue(qQNaN());
12 _temperature2Fact.setRawValue(qQNaN());
13 _temperature3Fact.setRawValue(qQNaN());
14}
15
16void VehicleTemperatureFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message)
17{
18 Q_UNUSED(vehicle);
19
20 switch (message.msgid) {
21 case MAVLINK_MSG_ID_SCALED_PRESSURE:
22 _handleScaledPressure(message);
23 break;
24 case MAVLINK_MSG_ID_SCALED_PRESSURE2:
25 _handleScaledPressure2(message);
26 break;
27 case MAVLINK_MSG_ID_SCALED_PRESSURE3:
28 _handleScaledPressure3(message);
29 break;
30 case MAVLINK_MSG_ID_HIGH_LATENCY:
31 _handleHighLatency(message);
32 break;
33 case MAVLINK_MSG_ID_HIGH_LATENCY2:
34 _handleHighLatency2(message);
35 break;
36 default:
37 break;
38 }
39}
40
41void VehicleTemperatureFactGroup::_handleHighLatency(const mavlink_message_t &message)
42{
43 mavlink_high_latency_t highLatency{};
44 mavlink_msg_high_latency_decode(&message, &highLatency);
45
46 temperature1()->setRawValue(highLatency.temperature_air);
47
49}
50
51void VehicleTemperatureFactGroup::_handleHighLatency2(const mavlink_message_t &message)
52{
53 mavlink_high_latency2_t highLatency2{};
54 mavlink_msg_high_latency2_decode(&message, &highLatency2);
55
56 temperature1()->setRawValue(highLatency2.temperature_air);
57
59}
60
61void VehicleTemperatureFactGroup::_handleScaledPressure(const mavlink_message_t &message)
62{
63 mavlink_scaled_pressure_t pressure{};
64 mavlink_msg_scaled_pressure_decode(&message, &pressure);
65
66 temperature1()->setRawValue(pressure.temperature / 100.0);
67
69}
70
71void VehicleTemperatureFactGroup::_handleScaledPressure2(const mavlink_message_t &message)
72{
73 mavlink_scaled_pressure2_t pressure{};
74 mavlink_msg_scaled_pressure2_decode(&message, &pressure);
75
76 temperature2()->setRawValue(pressure.temperature / 100.0);
77
79}
80
81void VehicleTemperatureFactGroup::_handleScaledPressure3(const mavlink_message_t &message)
82{
83 mavlink_scaled_pressure3_t pressure{};
84 mavlink_msg_scaled_pressure3_decode(&message, &pressure);
85
86 temperature3()->setRawValue(pressure.temperature / 100.0);
87
89}
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
void _setTelemetryAvailable(bool telemetryAvailable)
Definition FactGroup.cc:172