|
QGroundControl
Ground Control Station for MAVLink Drones
|
#include <VehicleGPSFactGroup.h>
Inheritance diagram for VehicleGPSFactGroup:
Collaboration diagram for VehicleGPSFactGroup:Signals | |
| void | gnssIntegrityReceived () |
Signals inherited from FactGroup | |
| void | factNamesChanged () |
| void | factGroupNamesChanged () |
| void | telemetryAvailableChanged (bool telemetryAvailable) |
Public Member Functions | |
| VehicleGPSFactGroup (QObject *parent=nullptr) | |
| Fact * | lat () |
| Fact * | lon () |
| Fact * | mgrs () |
| Fact * | hdop () |
| Fact * | vdop () |
| Fact * | courseOverGround () |
| Fact * | yaw () |
| Fact * | count () |
| Fact * | lock () |
| Fact * | systemErrors () |
| Fact * | spoofingState () |
| Fact * | jammingState () |
| Fact * | authenticationState () |
| Fact * | correctionsQuality () |
| Fact * | systemQuality () |
| Fact * | gnssSignalQuality () |
| Fact * | postProcessingQuality () |
| void | handleMessage (Vehicle *vehicle, const mavlink_message_t &message) override |
| Allows a FactGroup to parse incoming messages and fill in values. | |
Public Member Functions inherited from FactGroup | |
| FactGroup (int updateRateMsecs, const QString &metaDataFile, QObject *parent=nullptr, bool ignoreCamelCase=false) | |
| < false: No telemetry for these values has been received | |
| FactGroup (int updateRateMsecs, QObject *parent=nullptr, bool ignoreCamelCase=false) | |
| virtual | ~FactGroup () |
| Q_INVOKABLE bool | factExists (const QString &name) const |
| @ return true: if the fact exists in the group | |
| Q_INVOKABLE Fact * | getFact (const QString &name) const |
| Q_INVOKABLE FactGroup * | getFactGroup (const QString &name) const |
| Q_INVOKABLE void | setLiveUpdates (bool liveUpdates) |
| Turning on live updates will allow value changes to flow through as they are received. | |
| QStringList | factNames () const |
| QStringList | factGroupNames () const |
| bool | telemetryAvailable () const |
| const QMap< QString, FactGroup * > & | factGroups () const |
Protected Member Functions | |
| void | _handleGpsRawInt (const mavlink_message_t &message) |
| void | _handleHighLatency (const mavlink_message_t &message) |
| void | _handleHighLatency2 (const mavlink_message_t &message) |
| void | _handleGnssIntegrity (const mavlink_message_t &message) |
Protected Member Functions inherited from FactGroup | |
| void | _addFact (Fact *fact, const QString &name) |
| void | _addFact (Fact *fact) |
| void | _addFactGroup (FactGroup *factGroup, const QString &name) |
| void | _addFactGroup (FactGroup *factGroup) |
| void | _loadFromJsonArray (const QJsonArray &jsonArray) |
| void | _setTelemetryAvailable (bool telemetryAvailable) |
Additional Inherited Members | |
Protected Slots inherited from FactGroup | |
| virtual void | _updateAllValues () |
Definition at line 5 of file VehicleGPSFactGroup.h.
|
explicit |
Definition at line 9 of file VehicleGPSFactGroup.cc.
References FactGroup::_addFact(), _authenticationStateFact, _correctionsQualityFact, _countFact, _courseOverGroundFact, _gnssSignalQualityFact, _hdopFact, _jammingStateFact, _latFact, _lockFact, _lonFact, _mgrsFact, _postProcessingQualityFact, _spoofingStateFact, _systemErrorsFact, _systemQualityFact, _vdopFact, _yawFact, and Fact::setRawValue().
|
protected |
Definition at line 114 of file VehicleGPSFactGroup.cc.
References _gnssIntegrityId, authenticationState(), correctionsQuality(), gnssIntegrityReceived(), gnssSignalQuality(), jammingState(), postProcessingQuality(), Fact::setRawValue(), spoofingState(), systemErrors(), and systemQuality().
Referenced by VehicleGPS2FactGroup::handleMessage(), and handleMessage().
|
protected |
Definition at line 68 of file VehicleGPSFactGroup.cc.
References FactGroup::_setTelemetryAvailable(), QGCGeo::convertGeoToMGRS(), count(), courseOverGround(), hdop(), lat(), lock(), lon(), mgrs(), Fact::setRawValue(), vdop(), and yaw().
Referenced by handleMessage().
|
protected |
Definition at line 86 of file VehicleGPSFactGroup.cc.
References FactGroup::_setTelemetryAvailable(), QGCGeo::convertGeoToMGRS(), count(), lat(), lon(), mgrs(), and Fact::setRawValue().
Referenced by handleMessage().
|
protected |
Definition at line 99 of file VehicleGPSFactGroup.cc.
References FactGroup::_setTelemetryAvailable(), QGCGeo::convertGeoToMGRS(), count(), hdop(), lat(), lon(), mgrs(), Fact::setRawValue(), and vdop().
Referenced by handleMessage().
|
inline |
Definition at line 41 of file VehicleGPSFactGroup.h.
References _authenticationStateFact.
Referenced by _handleGnssIntegrity(), and VehicleGPSAggregateFactGroup::updateFromGps().
|
inline |
Definition at line 42 of file VehicleGPSFactGroup.h.
References _correctionsQualityFact.
Referenced by _handleGnssIntegrity().
|
inline |
Definition at line 36 of file VehicleGPSFactGroup.h.
References _countFact.
Referenced by _handleGpsRawInt(), _handleHighLatency(), and _handleHighLatency2().
|
inline |
Definition at line 34 of file VehicleGPSFactGroup.h.
References _courseOverGroundFact.
Referenced by _handleGpsRawInt().
|
signal |
Referenced by _handleGnssIntegrity(), and VehicleGPSAggregateFactGroup::bindToGps().
|
inline |
Definition at line 44 of file VehicleGPSFactGroup.h.
References _gnssSignalQualityFact.
Referenced by _handleGnssIntegrity().
|
overridevirtual |
Allows a FactGroup to parse incoming messages and fill in values.
Reimplemented from FactGroup.
Definition at line 46 of file VehicleGPSFactGroup.cc.
References _handleGnssIntegrity(), _handleGpsRawInt(), _handleHighLatency(), and _handleHighLatency2().
|
inline |
Definition at line 32 of file VehicleGPSFactGroup.h.
References _hdopFact.
Referenced by _handleGpsRawInt(), and _handleHighLatency2().
|
inline |
Definition at line 40 of file VehicleGPSFactGroup.h.
References _jammingStateFact.
Referenced by _handleGnssIntegrity(), and VehicleGPSAggregateFactGroup::updateFromGps().
|
inline |
Definition at line 29 of file VehicleGPSFactGroup.h.
References _latFact.
Referenced by _handleGpsRawInt(), _handleHighLatency(), and _handleHighLatency2().
|
inline |
Definition at line 37 of file VehicleGPSFactGroup.h.
References _lockFact.
Referenced by _handleGpsRawInt().
|
inline |
Definition at line 30 of file VehicleGPSFactGroup.h.
References _lonFact.
Referenced by _handleGpsRawInt(), _handleHighLatency(), and _handleHighLatency2().
|
inline |
Definition at line 31 of file VehicleGPSFactGroup.h.
References _mgrsFact.
Referenced by _handleGpsRawInt(), _handleHighLatency(), and _handleHighLatency2().
|
inline |
Definition at line 45 of file VehicleGPSFactGroup.h.
References _postProcessingQualityFact.
Referenced by _handleGnssIntegrity().
|
inline |
Definition at line 39 of file VehicleGPSFactGroup.h.
References _spoofingStateFact.
Referenced by _handleGnssIntegrity(), and VehicleGPSAggregateFactGroup::updateFromGps().
|
inline |
Definition at line 38 of file VehicleGPSFactGroup.h.
References _systemErrorsFact.
Referenced by _handleGnssIntegrity().
|
inline |
Definition at line 43 of file VehicleGPSFactGroup.h.
References _systemQualityFact.
Referenced by _handleGnssIntegrity().
|
inline |
Definition at line 33 of file VehicleGPSFactGroup.h.
References _vdopFact.
Referenced by _handleGpsRawInt(), and _handleHighLatency2().
|
inline |
Definition at line 35 of file VehicleGPSFactGroup.h.
References _yawFact.
Referenced by _handleGpsRawInt().
|
protected |
Definition at line 71 of file VehicleGPSFactGroup.h.
Referenced by authenticationState(), and VehicleGPSFactGroup().
|
protected |
Definition at line 72 of file VehicleGPSFactGroup.h.
Referenced by correctionsQuality(), and VehicleGPSFactGroup().
|
protected |
Definition at line 66 of file VehicleGPSFactGroup.h.
Referenced by count(), and VehicleGPSFactGroup().
|
protected |
Definition at line 64 of file VehicleGPSFactGroup.h.
Referenced by courseOverGround(), and VehicleGPSFactGroup().
|
protected |
Definition at line 77 of file VehicleGPSFactGroup.h.
Referenced by _handleGnssIntegrity(), and VehicleGPS2FactGroup::VehicleGPS2FactGroup().
|
protected |
Definition at line 74 of file VehicleGPSFactGroup.h.
Referenced by gnssSignalQuality(), and VehicleGPSFactGroup().
|
protected |
Definition at line 62 of file VehicleGPSFactGroup.h.
Referenced by hdop(), and VehicleGPSFactGroup().
|
protected |
Definition at line 70 of file VehicleGPSFactGroup.h.
Referenced by jammingState(), and VehicleGPSFactGroup().
|
protected |
Definition at line 59 of file VehicleGPSFactGroup.h.
Referenced by lat(), and VehicleGPSFactGroup().
|
protected |
Definition at line 67 of file VehicleGPSFactGroup.h.
Referenced by lock(), and VehicleGPSFactGroup().
|
protected |
Definition at line 60 of file VehicleGPSFactGroup.h.
Referenced by lon(), and VehicleGPSFactGroup().
|
protected |
Definition at line 61 of file VehicleGPSFactGroup.h.
Referenced by mgrs(), and VehicleGPSFactGroup().
|
protected |
Definition at line 75 of file VehicleGPSFactGroup.h.
Referenced by postProcessingQuality(), and VehicleGPSFactGroup().
|
protected |
Definition at line 69 of file VehicleGPSFactGroup.h.
Referenced by spoofingState(), and VehicleGPSFactGroup().
|
protected |
Definition at line 68 of file VehicleGPSFactGroup.h.
Referenced by systemErrors(), and VehicleGPSFactGroup().
|
protected |
Definition at line 73 of file VehicleGPSFactGroup.h.
Referenced by systemQuality(), and VehicleGPSFactGroup().
|
protected |
Definition at line 63 of file VehicleGPSFactGroup.h.
Referenced by vdop(), and VehicleGPSFactGroup().
|
protected |
Definition at line 65 of file VehicleGPSFactGroup.h.
Referenced by VehicleGPSFactGroup(), and yaw().