4VehicleRPMFactGroup::VehicleRPMFactGroup(QObject *parent)
5 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/RPMFact.json"), parent)
11 _addFact(&_rpmSensor1Fact);
12 _addFact(&_rpmSensor2Fact);
14 _rpm1Fact.setRawValue(qQNaN());
15 _rpm2Fact.setRawValue(qQNaN());
16 _rpm3Fact.setRawValue(qQNaN());
17 _rpm4Fact.setRawValue(qQNaN());
18 _rpmSensor1Fact.setRawValue(qQNaN());
19 _rpmSensor2Fact.setRawValue(qQNaN());
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) {
44 rpm1()->setRawValue(raw_rpm.frequency);
47 rpm2()->setRawValue(raw_rpm.frequency);
50 rpm3()->setRawValue(raw_rpm.frequency);
53 rpm4()->setRawValue(raw_rpm.frequency);
65 mavlink_msg_rpm_decode(&message, &rpm);
67 _rpmSensor1Fact.setRawValue(rpm.rpm1);
68 _rpmSensor2Fact.setRawValue(rpm.rpm2);
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)