diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index 838c19d..b3a0465 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -199,6 +199,7 @@ FlightMap { delegate: VehicleMapItem { coordinate: object.coordinate altitude: object.altitude + callsign: object.callsign heading: object.heading map: flightMap z: QGroundControl.zOrderVehicles diff --git a/src/FlightMap/MapItems/VehicleMapItem.qml b/src/FlightMap/MapItems/VehicleMapItem.qml index 2c86665..b914ebf 100644 --- a/src/FlightMap/MapItems/VehicleMapItem.qml +++ b/src/FlightMap/MapItems/VehicleMapItem.qml @@ -21,6 +21,7 @@ MapQuickItem { property var vehicle /// Vehicle object, undefined for ADSB vehicle property var map property double altitude: Number.NaN ///< NAN to not show + property string callsign: "" ///< Vehicle callsign property double heading: vehicle ? vehicle.heading.value : Number.NaN ///< Vehicle heading, NAN for none property real size: _adsbVehicle ? _adsbSize : _uavSize /// Size for icon @@ -65,7 +66,7 @@ MapQuickItem { property string vehicleLabelText: visible ? (_adsbVehicle ? - QGroundControl.metersToAppSettingsDistanceUnits(altitude).toFixed(0) + " " + QGroundControl.appSettingsDistanceUnitsString : + callsign + " " + QGroundControl.metersToAppSettingsDistanceUnits(altitude).toFixed(0) + " " + QGroundControl.appSettingsDistanceUnitsString : (_multiVehicle ? qsTr("Vehicle %1").arg(vehicle.id) : "")) : "" diff --git a/src/Vehicle/ADSBVehicle.cc b/src/Vehicle/ADSBVehicle.cc index e51d100..bd796cf 100644 --- a/src/Vehicle/ADSBVehicle.cc +++ b/src/Vehicle/ADSBVehicle.cc @@ -15,6 +15,7 @@ ADSBVehicle::ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent) : QObject (parent) , _icaoAddress (adsbVehicle.ICAO_address) + , _callsign (adsbVehicle.callsign) , _altitude (NAN) , _heading (NAN) { @@ -37,7 +38,14 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle) return; } - QGeoCoordinate newCoordinate(adsbVehicle.lat / qPow(10.0, 7.0), adsbVehicle.lon / qPow(10.0, 7.0)); + 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); @@ -45,7 +53,7 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle) double newAltitude = NAN; if (adsbVehicle.flags | ADSB_FLAGS_VALID_ALTITUDE) { - newAltitude = (double)adsbVehicle.altitude / 1000.0; + newAltitude = (double)adsbVehicle.altitude / 1e3; } if (!(qIsNaN(newAltitude) && qIsNaN(_altitude)) && !qFuzzyCompare(newAltitude, _altitude)) { _altitude = newAltitude; diff --git a/src/Vehicle/ADSBVehicle.h b/src/Vehicle/ADSBVehicle.h index a1ee26c..fe6046f 100644 --- a/src/Vehicle/ADSBVehicle.h +++ b/src/Vehicle/ADSBVehicle.h @@ -22,11 +22,13 @@ 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; } @@ -36,11 +38,13 @@ public: 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;