From 61baa666c4a709f0adf30aa62fdb1bdaa94c9705 Mon Sep 17 00:00:00 2001 From: Adam M Rivera Date: Fri, 29 Jun 2012 21:41:56 -0500 Subject: [PATCH] commands_process.pde: Bug fix 427. By default, the copter would land after an AUTO mission. Updated to check for valid approach altitude at end of mission. --- ArduCopter/commands_process.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/commands_process.pde b/ArduCopter/commands_process.pde index 4c3b94eda7..18132e284d 100644 --- a/ArduCopter/commands_process.pde +++ b/ArduCopter/commands_process.pde @@ -64,7 +64,8 @@ static void update_commands() if (land_complete == true){ // we will disarm the motors after landing. } else { - set_mode(LAND); + // If the approach altitude is valid (above 1m), do approach, else land + set_mode(((g.rtl_approach_alt >= 1) ? APPROACH : LAND)); } } }