4VehicleTemperatureFactGroup::VehicleTemperatureFactGroup(QObject *parent)
5 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/TemperatureFact.json"), parent)
7 _addFact(&_temperature1Fact);
8 _addFact(&_temperature2Fact);
9 _addFact(&_temperature3Fact);
11 _temperature1Fact.setRawValue(qQNaN());
12 _temperature2Fact.setRawValue(qQNaN());
13 _temperature3Fact.setRawValue(qQNaN());
20 switch (message.msgid) {
21 case MAVLINK_MSG_ID_SCALED_PRESSURE:
22 _handleScaledPressure(message);
24 case MAVLINK_MSG_ID_SCALED_PRESSURE2:
25 _handleScaledPressure2(message);
27 case MAVLINK_MSG_ID_SCALED_PRESSURE3:
28 _handleScaledPressure3(message);
30 case MAVLINK_MSG_ID_HIGH_LATENCY:
31 _handleHighLatency(message);
33 case MAVLINK_MSG_ID_HIGH_LATENCY2:
34 _handleHighLatency2(message);
41void VehicleTemperatureFactGroup::_handleHighLatency(
const mavlink_message_t &message)
43 mavlink_high_latency_t highLatency{};
44 mavlink_msg_high_latency_decode(&message, &highLatency);
46 temperature1()->setRawValue(highLatency.temperature_air);
51void VehicleTemperatureFactGroup::_handleHighLatency2(
const mavlink_message_t &message)
53 mavlink_high_latency2_t highLatency2{};
54 mavlink_msg_high_latency2_decode(&message, &highLatency2);
56 temperature1()->setRawValue(highLatency2.temperature_air);
61void VehicleTemperatureFactGroup::_handleScaledPressure(
const mavlink_message_t &message)
63 mavlink_scaled_pressure_t pressure{};
64 mavlink_msg_scaled_pressure_decode(&message, &pressure);
66 temperature1()->setRawValue(pressure.temperature / 100.0);
71void VehicleTemperatureFactGroup::_handleScaledPressure2(
const mavlink_message_t &message)
73 mavlink_scaled_pressure2_t pressure{};
74 mavlink_msg_scaled_pressure2_decode(&message, &pressure);
76 temperature2()->setRawValue(pressure.temperature / 100.0);
81void VehicleTemperatureFactGroup::_handleScaledPressure3(
const mavlink_message_t &message)
83 mavlink_scaled_pressure3_t pressure{};
84 mavlink_msg_scaled_pressure3_decode(&message, &pressure);
86 temperature3()->setRawValue(pressure.temperature / 100.0);
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)