From 004bda505bd54f34708fddf8e793d6a643f89bc5 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 8 Dec 2016 12:25:10 -0800 Subject: [PATCH] Correct guided mode AMSL versus Relative handling --- src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc | 7 +------ src/FlightDisplay/FlightDisplayViewWidgets.qml | 2 +- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index dd9350fa6..dee9bc789 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -120,16 +120,11 @@ void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle) void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitudeRel) { - if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) { - qgcApp()->showMessage(QStringLiteral("Unable to takeoff, vehicle position not known.")); - return; - } - vehicle->sendMavCommand(vehicle->defaultComponentId(), MAV_CMD_NAV_TAKEOFF, true, // show error 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, - vehicle->altitudeAMSL()->rawValue().toFloat() + altitudeRel); // AMSL meters + altitudeRel); } void ArduCopterFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) diff --git a/src/FlightDisplay/FlightDisplayViewWidgets.qml b/src/FlightDisplay/FlightDisplayViewWidgets.qml index 094a3fa25..7492de0d0 100644 --- a/src/FlightDisplay/FlightDisplayViewWidgets.qml +++ b/src/FlightDisplay/FlightDisplayViewWidgets.qml @@ -437,7 +437,7 @@ Item { break; case confirmChangeAlt: altitudeSlider.visible = true - altitudeSlider.setInitialValueAppSettingsDistanceUnits(_activeVehicle.altitudeAMSL.value) + altitudeSlider.setInitialValueAppSettingsDistanceUnits(_activeVehicle.altitudeRelative.value) guidedModeConfirm.confirmText = qsTr("change altitude") break; case confirmGoTo: -- 2.22.0