Browse Source

Correct guided mode AMSL versus Relative handling

QGC4.4
Don Gagne 8 years ago
parent
commit
004bda505b
  1. 7
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
  2. 2
      src/FlightDisplay/FlightDisplayViewWidgets.qml

7
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

@ -120,16 +120,11 @@ void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle) @@ -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)

2
src/FlightDisplay/FlightDisplayViewWidgets.qml

@ -437,7 +437,7 @@ Item { @@ -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:

Loading…
Cancel
Save