QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleRPMFactGroup.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4VehicleRPMFactGroup::VehicleRPMFactGroup(QObject *parent)
5 : FactGroup(1000, QStringLiteral(":/json/Vehicle/RPMFact.json"), parent)
6{
7 _addFact(&_rpm1Fact);
8 _addFact(&_rpm2Fact);
9 _addFact(&_rpm3Fact);
10 _addFact(&_rpm4Fact);
11 _addFact(&_rpmSensor1Fact);
12 _addFact(&_rpmSensor2Fact);
13
14 _rpm1Fact.setRawValue(qQNaN());
15 _rpm2Fact.setRawValue(qQNaN());
16 _rpm3Fact.setRawValue(qQNaN());
17 _rpm4Fact.setRawValue(qQNaN());
18 _rpmSensor1Fact.setRawValue(qQNaN());
19 _rpmSensor2Fact.setRawValue(qQNaN());
20}
21
22void VehicleRPMFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message)
23{
24 Q_UNUSED(vehicle);
25
26 switch (message.msgid) {
27 case MAVLINK_MSG_ID_RAW_RPM:
28 _handleRawRPM(message);
29 break;
30 case MAVLINK_MSG_ID_RPM:
31 _handleRPMSensor(message);
32 break;
33 default:
34 break;
35 }
36}
37
38void VehicleRPMFactGroup::_handleRawRPM(const mavlink_message_t &message)
39{
40 mavlink_raw_rpm_t raw_rpm{};
41 mavlink_msg_raw_rpm_decode(&message, &raw_rpm);
42 switch (raw_rpm.index) {
43 case 0:
44 rpm1()->setRawValue(raw_rpm.frequency);
45 break;
46 case 1:
47 rpm2()->setRawValue(raw_rpm.frequency);
48 break;
49 case 2:
50 rpm3()->setRawValue(raw_rpm.frequency);
51 break;
52 case 3:
53 rpm4()->setRawValue(raw_rpm.frequency);
54 break;
55 default:
56 break;
57 }
58
60}
61
62void VehicleRPMFactGroup::_handleRPMSensor(const mavlink_message_t &message)
63{
64 mavlink_rpm_t rpm{};
65 mavlink_msg_rpm_decode(&message, &rpm);
66
67 _rpmSensor1Fact.setRawValue(rpm.rpm1);
68 _rpmSensor2Fact.setRawValue(rpm.rpm2);
69
71}
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
void _setTelemetryAvailable(bool telemetryAvailable)
Definition FactGroup.cc:172