diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index 5bb0e891524af88b490510a85e5655d34f22811d..b20067a0a9cfe1953205ef7b81533c9745a59790 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -55,7 +55,7 @@ UASWaypointManager::UASWaypointManager(UAS* _uas) uasid = uas->getUASID(); connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout())); connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleLocalPositionChanged(UASInterface*,double,double,double,quint64))); - connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,double,double,quint64))); + connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,double,quint64))); } else { diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index a01796e46256496dc4d08958ec88511e81471070..99969c492e3b936db1c66c657dda8edf2563a01c 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -421,9 +421,10 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) * @param alt Altitude over mean sea level * @param usec Timestamp of the position message in milliseconds FIXME will move to microseconds */ -void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec) +void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double altAMSL, double altWGS84, quint64 usec) { Q_UNUSED(usec); + Q_UNUSED(altAMSL); // Immediate update if (maxUpdateInterval == 0) @@ -452,7 +453,7 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo // Set new lat/lon position of UAV icon internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon); - uav->SetUAVPos(pos_lat_lon, alt); + uav->SetUAVPos(pos_lat_lon, altWGS84); // Follow status if (followUAVEnabled && uas->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon); // Convert from radians to degrees and apply diff --git a/src/ui/map/QGCMapWidget.h b/src/ui/map/QGCMapWidget.h index 6fc17c6b32816687106c12f12be1b3b468787643..1550c7effc8ada58a56a1fa85ae843b74718ab25 100644 --- a/src/ui/map/QGCMapWidget.h +++ b/src/ui/map/QGCMapWidget.h @@ -56,7 +56,7 @@ public slots: /** @brief Add system to map view */ void addUAS(UASInterface* uas); /** @brief Update the global position of a system */ - void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec); + void updateGlobalPosition(UASInterface* uas, double lat, double lon, double altAMSL, double altWGS84, quint64 usec); /** @brief Update the global position of all systems */ void updateGlobalPosition(); /** @brief Update the local position and draw it converted to GPS reference */ diff --git a/src/ui/uas/UASView.cc b/src/ui/uas/UASView.cc index 4d5e1765d3e9ebcfca42b336d87275371678ddfe..ab86b3175b631dca611098caca76d421f61d8067 100644 --- a/src/ui/uas/UASView.cc +++ b/src/ui/uas/UASView.cc @@ -396,13 +396,14 @@ void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double localFrame = true; } -void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec) +void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double altAMSL, double altWGS84, quint64 usec) { Q_UNUSED(uas); Q_UNUSED(usec); + Q_UNUSED(altAMSL); this->lon = lon; this->lat = lat; - this->alt = alt; + this->alt = altWGS84; globalFrameKnown = true; } diff --git a/src/ui/uas/UASView.h b/src/ui/uas/UASView.h index 218f3a89584cee8fe0864bf976c197c55007d6be..c536d5be78fa7d2420fe2d64c0178cb898ae0298 100644 --- a/src/ui/uas/UASView.h +++ b/src/ui/uas/UASView.h @@ -58,7 +58,7 @@ public slots: void updateThrust(UASInterface* uas, double thrust); void updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds); void updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec); - void updateGlobalPosition(UASInterface*, double lon, double lat, double alt, quint64 usec); + void updateGlobalPosition(UASInterface*, double lon, double lat, double altAMSL, double altWGS84, quint64 usec); void updateSpeed(UASInterface*, double x, double y, double z, quint64 usec); void updateState(UASInterface*, QString uasState, QString stateDescription); /** @brief Update the MAV mode */