From 88896154d6feff0ab1dcfa16be2b5ffb3ca8d383 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 8 Aug 2024 14:56:39 +0930 Subject: [PATCH] Copter: Fix payload place bug --- ArduCopter/mode_auto.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 6a2b336b82..f07a6c363c 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1395,8 +1395,7 @@ void PayloadPlace::run() copter.flightmode->land_run_horizontal_control(); // update altitude target and call position controller pos_control->land_at_climb_rate_cm(-descent_speed_cms, true); - pos_control->update_z_controller(); - return; + break; case State::Release: case State::Releasing: case State::Delay: @@ -1404,8 +1403,7 @@ void PayloadPlace::run() copter.flightmode->land_run_horizontal_control(); // update altitude target and call position controller pos_control->land_at_climb_rate_cm(0.0, false); - pos_control->update_z_controller(); - return; + break; case State::Ascent: case State::Done: float vel = 0.0; @@ -1413,6 +1411,7 @@ void PayloadPlace::run() pos_control->input_pos_vel_accel_z(descent_start_altitude_cm, vel, 0.0); break; } + pos_control->update_z_controller(); } #endif