Plane:force min transition timer to 2 sec

This commit is contained in:
Henry Wurzburg 2023-10-15 21:04:01 -05:00 committed by Andrew Tridgell
parent 7d9cd3c1de
commit a26ee15216
1 changed files with 4 additions and 3 deletions

View File

@ -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,15 @@ 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) {
const float trans_time_ms = constrain_float(quadplane.transition_time_ms,2000,30000);
if (transition_timer_ms > unsigned(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;