|
|
@ -22,11 +22,13 @@ public: |
|
|
|
ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent = NULL); |
|
|
|
ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent = NULL); |
|
|
|
|
|
|
|
|
|
|
|
Q_PROPERTY(int icaoAddress READ icaoAddress CONSTANT) |
|
|
|
Q_PROPERTY(int icaoAddress READ icaoAddress CONSTANT) |
|
|
|
|
|
|
|
Q_PROPERTY(QString callsign READ callsign NOTIFY callsignChanged) |
|
|
|
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged) |
|
|
|
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged) |
|
|
|
Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged) // NaN for not available
|
|
|
|
Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged) // NaN for not available
|
|
|
|
Q_PROPERTY(double heading READ heading NOTIFY headingChanged) // NaN for not available
|
|
|
|
Q_PROPERTY(double heading READ heading NOTIFY headingChanged) // NaN for not available
|
|
|
|
|
|
|
|
|
|
|
|
int icaoAddress (void) const { return _icaoAddress; } |
|
|
|
int icaoAddress (void) const { return _icaoAddress; } |
|
|
|
|
|
|
|
QString callsign (void) const { return _callsign; } |
|
|
|
QGeoCoordinate coordinate (void) const { return _coordinate; } |
|
|
|
QGeoCoordinate coordinate (void) const { return _coordinate; } |
|
|
|
double altitude (void) const { return _altitude; } |
|
|
|
double altitude (void) const { return _altitude; } |
|
|
|
double heading (void) const { return _heading; } |
|
|
|
double heading (void) const { return _heading; } |
|
|
@ -36,11 +38,13 @@ public: |
|
|
|
|
|
|
|
|
|
|
|
signals: |
|
|
|
signals: |
|
|
|
void coordinateChanged(QGeoCoordinate coordinate); |
|
|
|
void coordinateChanged(QGeoCoordinate coordinate); |
|
|
|
|
|
|
|
void callsignChanged(QString callsign); |
|
|
|
void altitudeChanged(double altitude); |
|
|
|
void altitudeChanged(double altitude); |
|
|
|
void headingChanged(double heading); |
|
|
|
void headingChanged(double heading); |
|
|
|
|
|
|
|
|
|
|
|
private: |
|
|
|
private: |
|
|
|
uint32_t _icaoAddress; |
|
|
|
uint32_t _icaoAddress; |
|
|
|
|
|
|
|
QString _callsign; |
|
|
|
QGeoCoordinate _coordinate; |
|
|
|
QGeoCoordinate _coordinate; |
|
|
|
double _altitude; |
|
|
|
double _altitude; |
|
|
|
double _heading; |
|
|
|
double _heading; |
|
|
|