From 9d3224ef349495a88a2a03b36718f88bf357ee34 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 11 Feb 2013 11:40:36 +1100 Subject: [PATCH] Plane: fixed target speed reload on landing thanks to Doug for this fix! --- ArduPlane/commands_logic.pde | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index 2bc5c45e5d..460b94990f 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -350,11 +350,15 @@ static bool verify_land() gcs_send_text_fmt(PSTR("Land Complete - Hold course %ld"), hold_course); } - // reload any airspeed or groundspeed parameters that may have - // been set for landing - g.airspeed_cruise_cm.load(); - g.min_gndspeed_cm.load(); - g.throttle_cruise.load(); + if (g_gps->ground_speed*0.01 < 3.0) { + // reload any airspeed or groundspeed parameters that may have + // been set for landing. We don't do this till ground + // speed drops below 3.0 m/s as otherwise we will change + // target speeds too early. + g.airspeed_cruise_cm.load(); + g.min_gndspeed_cm.load(); + g.throttle_cruise.load(); + } } if (hold_course != -1) {