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
39public:
40 explicit VehicleFactGroup(QObject *parent = nullptr);
41
42 Fact *roll() { return &_rollFact; }
43 Fact *pitch() { return &_pitchFact; }
44 Fact *heading() { return &_headingFact; }
45 Fact *rollRate() { return &_rollRateFact; }
46 Fact *pitchRate() { return &_pitchRateFact; }
47 Fact *yawRate() { return &_yawRateFact; }
48 Fact *airSpeed() { return &_airSpeedFact; }
49 Fact *airSpeedSetpoint() { return &_airSpeedSetpointFact; }
50 Fact *groundSpeed() { return &_groundSpeedFact; }
51 Fact *climbRate() { return &_climbRateFact; }
52 Fact *altitudeRelative() { return &_altitudeRelativeFact; }
53 Fact *altitudeAMSL() { return &_altitudeAMSLFact; }
54 Fact *altitudeAboveTerr() { return &_altitudeAboveTerrFact; }
55 Fact *altitudeTuning() { return &_altitudeTuningFact; }
56 Fact *altitudeTuningSetpoint() { return &_altitudeTuningSetpointFact; }
57 Fact *xTrackError() { return &_xTrackErrorFact; }
58 Fact *rangeFinderDist() { return &_rangeFinderDistFact; }
59 Fact *flightDistance() { return &_flightDistanceFact; }
60 Fact *distanceToHome() { return &_distanceToHomeFact; }
61 Fact *timeToHome() { return &_timeToHomeFact; }
62 Fact *missionItemIndex() { return &_missionItemIndexFact; }
63 Fact *headingToNextWP() { return &_headingToNextWPFact; }
64 Fact *distanceToNextWP() { return &_distanceToNextWPFact; }
65 Fact *headingToHome() { return &_headingToHomeFact; }
66 Fact *headingFromHome() { return &_headingFromHomeFact; }
67 Fact *headingFromGCS() { return &_headingFromGCSFact; }
68 Fact *distanceToGCS() { return &_distanceToGCSFact; }
69 Fact *hobbs() { return &_hobbsFact; }
70 Fact *throttlePct() { return &_throttlePctFact; }
71 Fact *imuTemp() { return &_imuTempFact; }
72
73 void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override;
74
75protected:
76 void _handleAttitude(Vehicle *vehicle, const mavlink_message_t &message);
77 void _handleAttitudeQuaternion(Vehicle *vehicle, const mavlink_message_t &message);
78 void _handleAltitude(const mavlink_message_t &message);
79 void _handleVfrHud(const mavlink_message_t &message);
80 void _handleRawImuTemp(const mavlink_message_t &message);
82#ifndef QGC_NO_ARDUPILOT_DIALECT
83 void _handleRangefinder(const mavlink_message_t &message);
84#endif
85
86 Fact _rollFact = Fact(0, QStringLiteral("roll"), FactMetaData::valueTypeDouble);
87 Fact _pitchFact = Fact(0, QStringLiteral("pitch"), FactMetaData::valueTypeDouble);
88 Fact _headingFact = Fact(0, QStringLiteral("heading"), FactMetaData::valueTypeDouble);
89 Fact _rollRateFact = Fact(0, QStringLiteral("rollRate"), FactMetaData::valueTypeDouble);
90 Fact _pitchRateFact = Fact(0, QStringLiteral("pitchRate"), FactMetaData::valueTypeDouble);
91 Fact _yawRateFact = Fact(0, QStringLiteral("yawRate"), FactMetaData::valueTypeDouble);
92 Fact _groundSpeedFact = Fact(0, QStringLiteral("groundSpeed"), FactMetaData::valueTypeDouble);
93 Fact _airSpeedFact = Fact(0, QStringLiteral("airSpeed"), FactMetaData::valueTypeDouble);
94 Fact _airSpeedSetpointFact = Fact(0, QStringLiteral("airSpeedSetpoint"), FactMetaData::valueTypeDouble);
95 Fact _climbRateFact = Fact(0, QStringLiteral("climbRate"), FactMetaData::valueTypeDouble);
96 Fact _altitudeRelativeFact = Fact(0, QStringLiteral("altitudeRelative"), FactMetaData::valueTypeDouble);
97 Fact _altitudeAMSLFact = Fact(0, QStringLiteral("altitudeAMSL"), FactMetaData::valueTypeDouble);
98 Fact _altitudeAboveTerrFact = Fact(0, QStringLiteral("altitudeAboveTerr"), FactMetaData::valueTypeDouble);
99 Fact _altitudeTuningFact = Fact(0, QStringLiteral("altitudeTuning"), FactMetaData::valueTypeDouble);
100 Fact _altitudeTuningSetpointFact = Fact(0, QStringLiteral("altitudeTuningSetpoint"), FactMetaData::valueTypeDouble);
101 Fact _xTrackErrorFact = Fact(0, QStringLiteral("xTrackError"), FactMetaData::valueTypeDouble);
102 Fact _rangeFinderDistFact = Fact(0, QStringLiteral("rangeFinderDist"), FactMetaData::valueTypeFloat);
103 Fact _flightDistanceFact = Fact(0, QStringLiteral("flightDistance"), FactMetaData::valueTypeDouble);
105 Fact _distanceToHomeFact = Fact(0, QStringLiteral("distanceToHome"), FactMetaData::valueTypeDouble);
106 Fact _timeToHomeFact = Fact(0, QStringLiteral("timeToHome"), FactMetaData::valueTypeDouble);
107 Fact _missionItemIndexFact = Fact(0, QStringLiteral("missionItemIndex"), FactMetaData::valueTypeUint16);
108 Fact _headingToNextWPFact = Fact(0, QStringLiteral("headingToNextWP"), FactMetaData::valueTypeDouble);
109 Fact _distanceToNextWPFact = Fact(0, QStringLiteral("distanceToNextWP"), FactMetaData::valueTypeDouble);
110 Fact _headingToHomeFact = Fact(0, QStringLiteral("headingToHome"), FactMetaData::valueTypeDouble);
111 Fact _headingFromHomeFact = Fact(0, QStringLiteral("headingFromHome"),FactMetaData::valueTypeDouble);
112 Fact _headingFromGCSFact = Fact(0, QStringLiteral("headingFromGCS"),FactMetaData::valueTypeDouble);
113 Fact _distanceToGCSFact = Fact(0, QStringLiteral("distanceToGCS"), FactMetaData::valueTypeDouble);
114 Fact _hobbsFact = Fact(0, QStringLiteral("hobbs"), FactMetaData::valueTypeString);
115 Fact _throttlePctFact = Fact(0, QStringLiteral("throttlePct"), FactMetaData::valueTypeUint16);
116 Fact _imuTempFact = Fact(0, QStringLiteral("imuTemp"), FactMetaData::valueTypeInt16);
117
118 float _altitudeTuningOffset = qQNaN();
119
120protected:
122
123private:
124 void _handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians);
125
126 bool _receivingAttitudeQuaternion = false;
127};
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
@ valueTypeElapsedTimeInSeconds
A Fact is used to hold a single value within the system.
Definition Fact.h:19
void _handleAltitude(const mavlink_message_t &message)
void _handleNavControllerOutput(const mavlink_message_t &message)
void _handleAttitude(Vehicle *vehicle, const mavlink_message_t &message)
void _handleRawImuTemp(const mavlink_message_t &message)
void _handleVfrHud(const mavlink_message_t &message)
void _handleAttitudeQuaternion(Vehicle *vehicle, const mavlink_message_t &message)
void _handleRangefinder(const mavlink_message_t &message)