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)
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; }