From 14096d4eae6bbe6c442222ce46054b0acdafe128 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 23 Feb 2022 15:25:35 +1030 Subject: [PATCH] Copter: tighten auto_takeoff_complete checks --- ArduCopter/takeoff.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index 4f12db1256..7dfd4e2778 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -180,7 +180,7 @@ void Mode::auto_takeoff_run() // handle takeoff completion bool reached_altitude = (copter.pos_control->get_pos_target_z_cm() - auto_take_off_start_alt_cm) >= ((auto_take_off_complete_alt_cm - auto_take_off_start_alt_cm) * 0.90); - bool reached_climb_rate = copter.pos_control->get_vel_desired_cms().z < copter.pos_control->get_max_speed_up_cms() * 0.5; + bool reached_climb_rate = copter.pos_control->get_vel_desired_cms().z < copter.pos_control->get_max_speed_up_cms() * 0.1; auto_takeoff_complete = reached_altitude && reached_climb_rate; // calculate completion for location in case it is needed for a smooth transition to wp_nav