From ab42bbc43f5cd8cec5197c3dab7f8e175dc2cb8b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 14 Oct 2020 14:26:35 +0900 Subject: [PATCH] Copter: guided mode velocity control can trigger takeoff --- ArduCopter/mode_guided.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 28129c8fa3..ff4f1086ec 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -466,6 +466,17 @@ void ModeGuided::vel_control_run() } } + // landed with positive desired climb rate, initiate takeoff + if (motors->armed() && copter.ap.auto_armed && copter.ap.land_complete && is_positive(guided_vel_target_cms.z)) { + zero_throttle_and_relax_ac(); + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); + if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { + set_land_complete(false); + set_throttle_takeoff(); + } + return; + } + // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_spool_down();