From b299b9c0bb467f615240d1c5ba23f4cb36737696 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 6 Dec 2016 03:39:32 -0800 Subject: [PATCH] Plane: abstract out init_start_nav_cnd work to landing lib This reverts commit 1380a35f70ec985c96f59f2a9c5e42e0b5a3bc02. --- ArduPlane/commands_logic.cpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 29bb85cf3f..95285e6b7b 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -16,23 +16,16 @@ 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 - landing.complete = false; - landing.pre_flare = false; + landing.init_start_nav_cmd(); 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; - // if a go around had been commanded, clear it now. - landing.commanded_go_around = false; - // start non-idle auto_state.idle_mode = false; - // once landed, post some landing statistics to the GCS - landing.post_stats = false; - nav_controller->set_data_is_stale(); // reset loiter start time. New command is a new loiter