diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 8d7810d022..f2dd05e4a2 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -15,9 +15,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) // special handling for nav vs non-nav commands if (AP_Mission::is_nav_cmd(cmd)) { - // set land_complete to false to stop us zeroing the throttle - auto_state.sink_rate = 0; - // set takeoff_complete to true so we don't add extra elevator // except in a takeoff auto_state.takeoff_complete = true;