Commit 690cc596 authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #856 from mavlink/altitude

Add misssing arguments, fixes #847
parents 20ac1f34 64bd2058
...@@ -55,7 +55,7 @@ UASWaypointManager::UASWaypointManager(UAS* _uas) ...@@ -55,7 +55,7 @@ UASWaypointManager::UASWaypointManager(UAS* _uas)
uasid = uas->getUASID(); uasid = uas->getUASID();
connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout())); 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(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 else
{ {
......
...@@ -421,9 +421,10 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) ...@@ -421,9 +421,10 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
* @param alt Altitude over mean sea level * @param alt Altitude over mean sea level
* @param usec Timestamp of the position message in milliseconds FIXME will move to microseconds * @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(usec);
Q_UNUSED(altAMSL);
// Immediate update // Immediate update
if (maxUpdateInterval == 0) if (maxUpdateInterval == 0)
...@@ -452,7 +453,7 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo ...@@ -452,7 +453,7 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo
// Set new lat/lon position of UAV icon // Set new lat/lon position of UAV icon
internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon); internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
uav->SetUAVPos(pos_lat_lon, alt); uav->SetUAVPos(pos_lat_lon, altWGS84);
// Follow status // Follow status
if (followUAVEnabled && uas->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon); if (followUAVEnabled && uas->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
// Convert from radians to degrees and apply // Convert from radians to degrees and apply
......
...@@ -56,7 +56,7 @@ public slots: ...@@ -56,7 +56,7 @@ public slots:
/** @brief Add system to map view */ /** @brief Add system to map view */
void addUAS(UASInterface* uas); void addUAS(UASInterface* uas);
/** @brief Update the global position of a system */ /** @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 */ /** @brief Update the global position of all systems */
void updateGlobalPosition(); void updateGlobalPosition();
/** @brief Update the local position and draw it converted to GPS reference */ /** @brief Update the local position and draw it converted to GPS reference */
......
...@@ -396,13 +396,14 @@ void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double ...@@ -396,13 +396,14 @@ void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double
localFrame = true; 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(uas);
Q_UNUSED(usec); Q_UNUSED(usec);
Q_UNUSED(altAMSL);
this->lon = lon; this->lon = lon;
this->lat = lat; this->lat = lat;
this->alt = alt; this->alt = altWGS84;
globalFrameKnown = true; globalFrameKnown = true;
} }
......
...@@ -58,7 +58,7 @@ public slots: ...@@ -58,7 +58,7 @@ public slots:
void updateThrust(UASInterface* uas, double thrust); void updateThrust(UASInterface* uas, double thrust);
void updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds); void updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds);
void updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec); 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 updateSpeed(UASInterface*, double x, double y, double z, quint64 usec);
void updateState(UASInterface*, QString uasState, QString stateDescription); void updateState(UASInterface*, QString uasState, QString stateDescription);
/** @brief Update the MAV mode */ /** @brief Update the MAV mode */
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment