From 8ff8364252b225d1890ee6f277e67c7dfa5930d1 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 13 Mar 2018 15:27:03 +0900 Subject: [PATCH] Copter: remove redundant takeoff_stop from flowhold --- ArduCopter/mode_althold.cpp | 3 --- ArduCopter/mode_flowhold.cpp | 3 --- 2 files changed, 6 deletions(-) diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index 85e509f0f9..f0c94a1d91 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -18,9 +18,6 @@ bool Copter::ModeAltHold::init(bool ignore_checks) pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z()); } - // stop takeoff if running - takeoff_stop(); - return true; } diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index e3909055b0..c278faac3a 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -103,9 +103,6 @@ bool Copter::ModeFlowHold::init(bool ignore_checks) quality_filtered = 0; flow_pi_xy.reset_I(); limited = false; - - // stop takeoff if running - copter.takeoff_stop(); flow_pi_xy.set_dt(1.0/copter.scheduler.get_loop_rate_hz());