5 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/RPMFact.json"), parent)
26 switch (message.msgid) {
27 case MAVLINK_MSG_ID_RAW_RPM:
28 _handleRawRPM(message);
30 case MAVLINK_MSG_ID_RPM:
31 _handleRPMSensor(message);
40 mavlink_raw_rpm_t raw_rpm{};
41 mavlink_msg_raw_rpm_decode(&message, &raw_rpm);
42 switch (raw_rpm.index) {
65 mavlink_msg_rpm_decode(&message, &rpm);
struct __mavlink_message mavlink_message_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.
VehicleRPMFactGroup(QObject *parent=nullptr)