diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 804fe8ef1c..cba340eca0 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -500,6 +500,7 @@ static void do_change_alt() // To-Do; reset origin to current location + stopping distance at new altitude break; case Auto_Land: + case Auto_RTL: // ignore altitude break; case Auto_Circle: diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 183cb4394c..2eb567b7c2 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -193,7 +193,6 @@ enum AutoMode { // RTL states enum RTLState { - Start, InitialClimb, ReturnHome, LoiterAtHome,