5 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/TemperatureFact.json"), parent)
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);
51void VehicleTemperatureFactGroup::_handleHighLatency2(
const mavlink_message_t &message)
54 mavlink_msg_high_latency2_decode(&message, &highLatency2);
61void VehicleTemperatureFactGroup::_handleScaledPressure(
const mavlink_message_t &message)
63 mavlink_scaled_pressure_t pressure{};
64 mavlink_msg_scaled_pressure_decode(&message, &pressure);
71void VehicleTemperatureFactGroup::_handleScaledPressure2(
const mavlink_message_t &message)
73 mavlink_scaled_pressure2_t pressure{};
74 mavlink_msg_scaled_pressure2_decode(&message, &pressure);
81void VehicleTemperatureFactGroup::_handleScaledPressure3(
const mavlink_message_t &message)
83 mavlink_scaled_pressure3_t pressure{};
84 mavlink_msg_scaled_pressure3_decode(&message, &pressure);
struct __mavlink_message mavlink_message_t
struct __mavlink_high_latency2_t mavlink_high_latency2_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)
void _addFact(Fact *fact, const QString &name)
void setRawValue(const QVariant &value)
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final
Allows a FactGroup to parse incoming messages and fill in values.
VehicleTemperatureFactGroup(QObject *parent=nullptr)