From 3ac121dbc1ea7ffe11402d50fd461bcfa546383c Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 15 Oct 2023 21:04:01 -0500 Subject: [PATCH] Plane:force min transition timer to 2 sec --- ArduPlane/quadplane.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 9557637af40d58..42ffdf53d9a47c 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -33,7 +33,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @DisplayName: Transition time // @Description: Transition time in milliseconds after minimum airspeed is reached // @Units: ms - // @Range: 1 30000 + // @Range: 2000 30000 // @User: Advanced AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000), @@ -1699,14 +1699,14 @@ void SLT_Transition::update() // after airspeed is reached we degrade throttle over the // transition time, but continue to stabilize const uint32_t transition_timer_ms = now - transition_low_airspeed_ms; - if (transition_timer_ms > (unsigned)quadplane.transition_time_ms) { + if (transition_timer_ms > trans_time_ms) { transition_state = TRANSITION_DONE; in_forced_transition = false; transition_start_ms = 0; transition_low_airspeed_ms = 0; gcs().send_text(MAV_SEVERITY_INFO, "Transition done"); } - float trans_time_ms = MAX((float)quadplane.transition_time_ms.get(),1); + float transition_scale = (trans_time_ms - transition_timer_ms) / trans_time_ms; float throttle_scaled = last_throttle * transition_scale;