QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleEstimatorStatusFactGroup.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 *goodAttitudeEstimate READ goodAttitudeEstimate CONSTANT)
9 Q_PROPERTY(Fact *goodHorizVelEstimate READ goodHorizVelEstimate CONSTANT)
10 Q_PROPERTY(Fact *goodVertVelEstimate READ goodVertVelEstimate CONSTANT)
11 Q_PROPERTY(Fact *goodHorizPosRelEstimate READ goodHorizPosRelEstimate CONSTANT)
12 Q_PROPERTY(Fact *goodHorizPosAbsEstimate READ goodHorizPosAbsEstimate CONSTANT)
13 Q_PROPERTY(Fact *goodVertPosAbsEstimate READ goodVertPosAbsEstimate CONSTANT)
14 Q_PROPERTY(Fact *goodVertPosAGLEstimate READ goodVertPosAGLEstimate CONSTANT)
15 Q_PROPERTY(Fact *goodConstPosModeEstimate READ goodConstPosModeEstimate CONSTANT)
16 Q_PROPERTY(Fact *goodPredHorizPosRelEstimate READ goodPredHorizPosRelEstimate CONSTANT)
17 Q_PROPERTY(Fact *goodPredHorizPosAbsEstimate READ goodPredHorizPosAbsEstimate CONSTANT)
18 Q_PROPERTY(Fact *gpsGlitch READ gpsGlitch CONSTANT)
19 Q_PROPERTY(Fact *accelError READ accelError CONSTANT)
20 Q_PROPERTY(Fact *velRatio READ velRatio CONSTANT)
21 Q_PROPERTY(Fact *horizPosRatio READ horizPosRatio CONSTANT)
22 Q_PROPERTY(Fact *vertPosRatio READ vertPosRatio CONSTANT)
23 Q_PROPERTY(Fact *magRatio READ magRatio CONSTANT)
24 Q_PROPERTY(Fact *haglRatio READ haglRatio CONSTANT)
25 Q_PROPERTY(Fact *tasRatio READ tasRatio CONSTANT)
26 Q_PROPERTY(Fact *horizPosAccuracy READ horizPosAccuracy CONSTANT)
27 Q_PROPERTY(Fact *vertPosAccuracy READ vertPosAccuracy CONSTANT)
28
29public:
30 explicit VehicleEstimatorStatusFactGroup(QObject *parent = nullptr);
31
32 Fact *goodAttitudeEstimate() { return &_goodAttitudeEstimateFact; }
33 Fact *goodHorizVelEstimate() { return &_goodHorizVelEstimateFact; }
34 Fact *goodVertVelEstimate() { return &_goodVertVelEstimateFact; }
35 Fact *goodHorizPosRelEstimate() { return &_goodHorizPosRelEstimateFact; }
36 Fact *goodHorizPosAbsEstimate() { return &_goodHorizPosAbsEstimateFact; }
37 Fact *goodVertPosAbsEstimate() { return &_goodVertPosAbsEstimateFact; }
38 Fact *goodVertPosAGLEstimate() { return &_goodVertPosAGLEstimateFact; }
39 Fact *goodConstPosModeEstimate() { return &_goodConstPosModeEstimateFact; }
40 Fact *goodPredHorizPosRelEstimate() { return &_goodPredHorizPosRelEstimateFact; }
41 Fact *goodPredHorizPosAbsEstimate() { return &_goodPredHorizPosAbsEstimateFact; }
42 Fact *gpsGlitch() { return &_gpsGlitchFact; }
43 Fact *accelError() { return &_accelErrorFact; }
44 Fact *velRatio() { return &_velRatioFact; }
45 Fact *horizPosRatio() { return &_horizPosRatioFact; }
46 Fact *vertPosRatio() { return &_vertPosRatioFact; }
47 Fact *magRatio() { return &_magRatioFact; }
48 Fact *haglRatio() { return &_haglRatioFact; }
49 Fact *tasRatio() { return &_tasRatioFact; }
50 Fact *horizPosAccuracy() { return &_horizPosAccuracyFact; }
51 Fact *vertPosAccuracy() { return &_vertPosAccuracyFact; }
52
53 // Overrides from FactGroup
54 void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final;
55
56private:
57 Fact _goodAttitudeEstimateFact = Fact(0, QStringLiteral("goodAttitudeEsimate"), FactMetaData::valueTypeBool);
58 Fact _goodHorizVelEstimateFact = Fact(0, QStringLiteral("goodHorizVelEstimate"), FactMetaData::valueTypeBool);
59 Fact _goodVertVelEstimateFact = Fact(0, QStringLiteral("goodVertVelEstimate"), FactMetaData::valueTypeBool);
60 Fact _goodHorizPosRelEstimateFact = Fact(0, QStringLiteral("goodHorizPosRelEstimate"), FactMetaData::valueTypeBool);
61 Fact _goodHorizPosAbsEstimateFact = Fact(0, QStringLiteral("goodHorizPosAbsEstimate"), FactMetaData::valueTypeBool);
62 Fact _goodVertPosAbsEstimateFact = Fact(0, QStringLiteral("goodVertPosAbsEstimate"), FactMetaData::valueTypeBool);
63 Fact _goodVertPosAGLEstimateFact = Fact(0, QStringLiteral("goodVertPosAGLEstimate"), FactMetaData::valueTypeBool);
64 Fact _goodConstPosModeEstimateFact = Fact(0, QStringLiteral("goodConstPosModeEstimate"), FactMetaData::valueTypeBool);
65 Fact _goodPredHorizPosRelEstimateFact = Fact(0, QStringLiteral("goodPredHorizPosRelEstimate"), FactMetaData::valueTypeBool);
66 Fact _goodPredHorizPosAbsEstimateFact = Fact(0, QStringLiteral("goodPredHorizPosAbsEstimate"), FactMetaData::valueTypeBool);
67 Fact _gpsGlitchFact = Fact(0, QStringLiteral("gpsGlitch"), FactMetaData::valueTypeBool);
68 Fact _accelErrorFact = Fact(0, QStringLiteral("accelError"), FactMetaData::valueTypeBool);
69 Fact _velRatioFact = Fact(0, QStringLiteral("velRatio"), FactMetaData::valueTypeFloat);
70 Fact _horizPosRatioFact = Fact(0, QStringLiteral("horizPosRatio"), FactMetaData::valueTypeFloat);
71 Fact _vertPosRatioFact = Fact(0, QStringLiteral("vertPosRatio"), FactMetaData::valueTypeFloat);
72 Fact _magRatioFact = Fact(0, QStringLiteral("magRatio"), FactMetaData::valueTypeFloat);
73 Fact _haglRatioFact = Fact(0, QStringLiteral("haglRatio"), FactMetaData::valueTypeFloat);
74 Fact _tasRatioFact = Fact(0, QStringLiteral("tasRatio"), FactMetaData::valueTypeFloat);
75 Fact _horizPosAccuracyFact = Fact(0, QStringLiteral("horizPosAccuracy"), FactMetaData::valueTypeFloat);
76 Fact _vertPosAccuracyFact = Fact(0, QStringLiteral("vertPosAccuracy"), FactMetaData::valueTypeFloat);
77};
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
A Fact is used to hold a single value within the system.
Definition Fact.h:19