QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleFactGroup.h
Go to the documentation of this file.
1#pragma once
2
3#include "FactGroup.h"
4
6{
7 Q_OBJECT
8 Q_PROPERTY(Fact *roll READ roll CONSTANT)
9 Q_PROPERTY(Fact *pitch READ pitch CONSTANT)
10 Q_PROPERTY(Fact *heading READ heading CONSTANT)
11 Q_PROPERTY(Fact *rollRate READ rollRate CONSTANT)
12 Q_PROPERTY(Fact *pitchRate READ pitchRate CONSTANT)
13 Q_PROPERTY(Fact *yawRate READ yawRate CONSTANT)
14 Q_PROPERTY(Fact *groundSpeed READ groundSpeed CONSTANT)
15 Q_PROPERTY(Fact *airSpeed READ airSpeed CONSTANT)
16 Q_PROPERTY(Fact *airSpeedSetpoint READ airSpeedSetpoint CONSTANT)
17 Q_PROPERTY(Fact *climbRate READ climbRate CONSTANT)
18 Q_PROPERTY(Fact *altitudeRelative READ altitudeRelative CONSTANT)
19 Q_PROPERTY(Fact *altitudeAMSL READ altitudeAMSL CONSTANT)
20 Q_PROPERTY(Fact *altitudeAboveTerr READ altitudeAboveTerr CONSTANT)
21 Q_PROPERTY(Fact *altitudeTuning READ altitudeTuning CONSTANT)
22 Q_PROPERTY(Fact *altitudeTuningSetpoint READ altitudeTuningSetpoint CONSTANT)
23 Q_PROPERTY(Fact *xTrackError READ xTrackError CONSTANT)
24 Q_PROPERTY(Fact *rangeFinderDist READ rangeFinderDist CONSTANT)
25 Q_PROPERTY(Fact *flightDistance READ flightDistance CONSTANT)
26 Q_PROPERTY(Fact *distanceToHome READ distanceToHome CONSTANT)
27 Q_PROPERTY(Fact *timeToHome READ timeToHome CONSTANT)
28 Q_PROPERTY(Fact *missionItemIndex READ missionItemIndex CONSTANT)
29 Q_PROPERTY(Fact *headingToNextWP READ headingToNextWP CONSTANT)
30 Q_PROPERTY(Fact *distanceToNextWP READ distanceToNextWP CONSTANT)
31 Q_PROPERTY(Fact *headingToHome READ headingToHome CONSTANT)
32 Q_PROPERTY(Fact *headingFromHome READ headingFromHome CONSTANT)
33 Q_PROPERTY(Fact *headingFromGCS READ headingFromGCS CONSTANT)
34 Q_PROPERTY(Fact *distanceToGCS READ distanceToGCS CONSTANT)
35 Q_PROPERTY(Fact *hobbs READ hobbs CONSTANT)
36 Q_PROPERTY(Fact *throttlePct READ throttlePct CONSTANT)
37 Q_PROPERTY(Fact *imuTemp READ imuTemp CONSTANT)
38 Q_PROPERTY(Fact *rcRSSI READ rcRSSI CONSTANT)
39
40public:
41 explicit VehicleFactGroup(QObject *parent = nullptr);
42
43 Fact *roll() { return &_rollFact; }
44 Fact *pitch() { return &_pitchFact; }
45 Fact *heading() { return &_headingFact; }
46 Fact *rollRate() { return &_rollRateFact; }
48 Fact *yawRate() { return &_yawRateFact; }
49 Fact *airSpeed() { return &_airSpeedFact; }
70 Fact *hobbs() { return &_hobbsFact; }
72 Fact *imuTemp() { return &_imuTempFact; }
73 Fact *rcRSSI() { return &_rcRSSIFact; }
74
75 void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override;
76
79 void updateRCRSSI(uint8_t rssi);
80
81protected:
82 void _handleAttitude(Vehicle *vehicle, const mavlink_message_t &message);
83 void _handleAttitudeQuaternion(Vehicle *vehicle, const mavlink_message_t &message);
84 void _handleAltitude(const mavlink_message_t &message);
85 void _handleVfrHud(const mavlink_message_t &message);
86 void _handleRawImuTemp(const mavlink_message_t &message);
88#ifndef QGC_NO_ARDUPILOT_DIALECT
89 void _handleRangefinder(const mavlink_message_t &message);
90#endif
91
92 Fact _rollFact = Fact(0, QStringLiteral("roll"), FactMetaData::valueTypeDouble);
93 Fact _pitchFact = Fact(0, QStringLiteral("pitch"), FactMetaData::valueTypeDouble);
94 Fact _headingFact = Fact(0, QStringLiteral("heading"), FactMetaData::valueTypeDouble);
95 Fact _rollRateFact = Fact(0, QStringLiteral("rollRate"), FactMetaData::valueTypeDouble);
96 Fact _pitchRateFact = Fact(0, QStringLiteral("pitchRate"), FactMetaData::valueTypeDouble);
97 Fact _yawRateFact = Fact(0, QStringLiteral("yawRate"), FactMetaData::valueTypeDouble);
98 Fact _groundSpeedFact = Fact(0, QStringLiteral("groundSpeed"), FactMetaData::valueTypeDouble);
99 Fact _airSpeedFact = Fact(0, QStringLiteral("airSpeed"), FactMetaData::valueTypeDouble);
100 Fact _airSpeedSetpointFact = Fact(0, QStringLiteral("airSpeedSetpoint"), FactMetaData::valueTypeDouble);
101 Fact _climbRateFact = Fact(0, QStringLiteral("climbRate"), FactMetaData::valueTypeDouble);
102 Fact _altitudeRelativeFact = Fact(0, QStringLiteral("altitudeRelative"), FactMetaData::valueTypeDouble);
103 Fact _altitudeAMSLFact = Fact(0, QStringLiteral("altitudeAMSL"), FactMetaData::valueTypeDouble);
104 Fact _altitudeAboveTerrFact = Fact(0, QStringLiteral("altitudeAboveTerr"), FactMetaData::valueTypeDouble);
105 Fact _altitudeTuningFact = Fact(0, QStringLiteral("altitudeTuning"), FactMetaData::valueTypeDouble);
106 Fact _altitudeTuningSetpointFact = Fact(0, QStringLiteral("altitudeTuningSetpoint"), FactMetaData::valueTypeDouble);
107 Fact _xTrackErrorFact = Fact(0, QStringLiteral("xTrackError"), FactMetaData::valueTypeDouble);
108 Fact _rangeFinderDistFact = Fact(0, QStringLiteral("rangeFinderDist"), FactMetaData::valueTypeFloat);
109 Fact _flightDistanceFact = Fact(0, QStringLiteral("flightDistance"), FactMetaData::valueTypeDouble);
111 Fact _distanceToHomeFact = Fact(0, QStringLiteral("distanceToHome"), FactMetaData::valueTypeDouble);
112 Fact _timeToHomeFact = Fact(0, QStringLiteral("timeToHome"), FactMetaData::valueTypeDouble);
113 Fact _missionItemIndexFact = Fact(0, QStringLiteral("missionItemIndex"), FactMetaData::valueTypeUint16);
114 Fact _headingToNextWPFact = Fact(0, QStringLiteral("headingToNextWP"), FactMetaData::valueTypeDouble);
115 Fact _distanceToNextWPFact = Fact(0, QStringLiteral("distanceToNextWP"), FactMetaData::valueTypeDouble);
116 Fact _headingToHomeFact = Fact(0, QStringLiteral("headingToHome"), FactMetaData::valueTypeDouble);
117 Fact _headingFromHomeFact = Fact(0, QStringLiteral("headingFromHome"),FactMetaData::valueTypeDouble);
118 Fact _headingFromGCSFact = Fact(0, QStringLiteral("headingFromGCS"),FactMetaData::valueTypeDouble);
119 Fact _distanceToGCSFact = Fact(0, QStringLiteral("distanceToGCS"), FactMetaData::valueTypeDouble);
120 Fact _hobbsFact = Fact(0, QStringLiteral("hobbs"), FactMetaData::valueTypeString);
121 Fact _throttlePctFact = Fact(0, QStringLiteral("throttlePct"), FactMetaData::valueTypeUint16);
122 Fact _imuTempFact = Fact(0, QStringLiteral("imuTemp"), FactMetaData::valueTypeInt16);
123 Fact _rcRSSIFact = Fact(0, QStringLiteral("rcRSSI"), FactMetaData::valueTypeUint8);
124
125 float _altitudeTuningOffset = qQNaN();
126
127protected:
129
130private:
131 void _handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians);
132
133 bool _receivingAttitudeQuaternion = false;
134
135 // Low-pass filter state for rcRSSI. 255 is the sentinel "invalid/uninitialized" value.
136 double _rcRSSIStore = 255.0;
137};
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
@ valueTypeElapsedTimeInSeconds
A Fact is used to hold a single value within the system.
Definition Fact.h:17
void _handleAltitude(const mavlink_message_t &message)
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override
Allows a FactGroup to parse incoming messages and fill in values.
void _handleNavControllerOutput(const mavlink_message_t &message)
void _handleAttitude(Vehicle *vehicle, const mavlink_message_t &message)
void _handleRawImuTemp(const mavlink_message_t &message)
void updateRCRSSI(uint8_t rssi)
void _handleVfrHud(const mavlink_message_t &message)
void _handleAttitudeQuaternion(Vehicle *vehicle, const mavlink_message_t &message)
Fact * altitudeTuningSetpoint()
void _handleRangefinder(const mavlink_message_t &message)