4VehicleHygrometerFactGroup::VehicleHygrometerFactGroup(QObject *parent)
5 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/HygrometerFact.json"), parent)
7 _addFact(&_hygroTempFact);
8 _addFact(&_hygroHumiFact);
9 _addFact(&_hygroIDFact);
11 _hygroTempFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
12 _hygroHumiFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
13 _hygroIDFact.setRawValue(std::numeric_limits<unsigned int>::quiet_NaN());
20 switch (message.msgid) {
21 case MAVLINK_MSG_ID_HYGROMETER_SENSOR:
31 mavlink_hygrometer_sensor_t hygrometer{};
32 mavlink_msg_hygrometer_sensor_decode(&message, &hygrometer);
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)
void _handleHygrometerSensor(const mavlink_message_t &message)