Browse Source
* 'master' of https://github.com/mavlink/qgroundcontrol: (37 commits) Update ISSUE_TEMPLATE.md Update ISSUE_TEMPLATE.md Create ISSUE_TEMPLATE.md Revert "Remove FileManager unit test" Revert "Temp removal of Onboard File" FileManager: fix upload complete QGCUASFileView.cc: fix upload complete Flight display: Fixed TypeErrors on startup without gstream installed Fix timeout logic 10 sec timeout on vehicle Stack callsign below altitude Flight display: Create property variable Flight display: Remove video record button when gstreamer is not installed Add missing lib Flight display: Add callsign to transponders Add missing lib Better display of vehicle indicators for multi-vehicle Add support for ADSB vehicle display travis-ci fix indentation travis-ci fix google play deploy and quiet wget ...QGC4.4
34 changed files with 749 additions and 315 deletions
@ -0,0 +1,4 @@ |
|||||||
|
Note: GitHub Issues are for bugs or feature requests only. Do not enter Issues for questions regarding usage or problems building QGC yourself. |
||||||
|
Use the appropriate support channel instead: http://qgroundcontrol.com/#resources. |
||||||
|
|
||||||
|
Delete all of this text when create a real bug Issue. |
@ -0,0 +1,71 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||||
|
* |
||||||
|
* QGroundControl is licensed according to the terms in the file |
||||||
|
* COPYING.md in the root of the source code directory. |
||||||
|
* |
||||||
|
****************************************************************************/ |
||||||
|
|
||||||
|
#include "ADSBVehicle.h" |
||||||
|
|
||||||
|
#include <QDebug> |
||||||
|
#include <QtMath> |
||||||
|
|
||||||
|
ADSBVehicle::ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent) |
||||||
|
: QObject (parent) |
||||||
|
, _icaoAddress (adsbVehicle.ICAO_address) |
||||||
|
, _callsign (adsbVehicle.callsign) |
||||||
|
, _altitude (NAN) |
||||||
|
, _heading (NAN) |
||||||
|
{ |
||||||
|
if (!(adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS)) { |
||||||
|
qWarning() << "At least coords must be valid"; |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
update(adsbVehicle); |
||||||
|
} |
||||||
|
|
||||||
|
void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle) |
||||||
|
{ |
||||||
|
if (_icaoAddress != adsbVehicle.ICAO_address) { |
||||||
|
qWarning() << "ICAO address mismatch expected:actual" << _icaoAddress << adsbVehicle.ICAO_address; |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
if (!(adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS)) { |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
QString currCallsign(adsbVehicle.callsign); |
||||||
|
|
||||||
|
if (currCallsign != _callsign) { |
||||||
|
_callsign = currCallsign; |
||||||
|
emit callsignChanged(_callsign); |
||||||
|
} |
||||||
|
|
||||||
|
QGeoCoordinate newCoordinate(adsbVehicle.lat / 1e7, adsbVehicle.lon / 1e7); |
||||||
|
if (newCoordinate != _coordinate) { |
||||||
|
_coordinate = newCoordinate; |
||||||
|
emit coordinateChanged(_coordinate); |
||||||
|
} |
||||||
|
|
||||||
|
double newAltitude = NAN; |
||||||
|
if (adsbVehicle.flags | ADSB_FLAGS_VALID_ALTITUDE) { |
||||||
|
newAltitude = (double)adsbVehicle.altitude / 1e3; |
||||||
|
} |
||||||
|
if (!(qIsNaN(newAltitude) && qIsNaN(_altitude)) && !qFuzzyCompare(newAltitude, _altitude)) { |
||||||
|
_altitude = newAltitude; |
||||||
|
emit altitudeChanged(_altitude); |
||||||
|
} |
||||||
|
|
||||||
|
double newHeading = NAN; |
||||||
|
if (adsbVehicle.flags | ADSB_FLAGS_VALID_HEADING) { |
||||||
|
newHeading = (double)adsbVehicle.heading / 100.0; |
||||||
|
} |
||||||
|
if (!(qIsNaN(newHeading) && qIsNaN(_heading)) && !qFuzzyCompare(newHeading, _heading)) { |
||||||
|
_heading = newHeading; |
||||||
|
emit headingChanged(_heading); |
||||||
|
} |
||||||
|
} |
@ -0,0 +1,51 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||||
|
* |
||||||
|
* QGroundControl is licensed according to the terms in the file |
||||||
|
* COPYING.md in the root of the source code directory. |
||||||
|
* |
||||||
|
****************************************************************************/ |
||||||
|
|
||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <QObject> |
||||||
|
#include <QGeoCoordinate> |
||||||
|
|
||||||
|
#include "QGCMAVLink.h" |
||||||
|
|
||||||
|
class ADSBVehicle : public QObject |
||||||
|
{ |
||||||
|
Q_OBJECT |
||||||
|
|
||||||
|
public: |
||||||
|
ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent = NULL); |
||||||
|
|
||||||
|
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(double altitude READ altitude NOTIFY altitudeChanged) // NaN for not available
|
||||||
|
Q_PROPERTY(double heading READ heading NOTIFY headingChanged) // NaN for not available
|
||||||
|
|
||||||
|
int icaoAddress (void) const { return _icaoAddress; } |
||||||
|
QString callsign (void) const { return _callsign; } |
||||||
|
QGeoCoordinate coordinate (void) const { return _coordinate; } |
||||||
|
double altitude (void) const { return _altitude; } |
||||||
|
double heading (void) const { return _heading; } |
||||||
|
|
||||||
|
/// Update the vehicle with new information
|
||||||
|
void update(mavlink_adsb_vehicle_t& adsbVehicle); |
||||||
|
|
||||||
|
signals: |
||||||
|
void coordinateChanged(QGeoCoordinate coordinate); |
||||||
|
void callsignChanged(QString callsign); |
||||||
|
void altitudeChanged(double altitude); |
||||||
|
void headingChanged(double heading); |
||||||
|
|
||||||
|
private: |
||||||
|
uint32_t _icaoAddress; |
||||||
|
QString _callsign; |
||||||
|
QGeoCoordinate _coordinate; |
||||||
|
double _altitude; |
||||||
|
double _heading; |
||||||
|
}; |
Loading…
Reference in new issue