mirror of https://github.com/ArduPilot/ardupilot
Plane: drop min Q_TRANSITION_MS to 500ms
Rolf makes a good argument for why some quadplanes need less than 2s
This commit is contained in:
parent
f83cde7760
commit
5e3f26744a
|
@ -33,7 +33,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
||||||
// @DisplayName: Transition time
|
// @DisplayName: Transition time
|
||||||
// @Description: Transition time in milliseconds after minimum airspeed is reached
|
// @Description: Transition time in milliseconds after minimum airspeed is reached
|
||||||
// @Units: ms
|
// @Units: ms
|
||||||
// @Range: 2000 30000
|
// @Range: 500 30000
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000),
|
AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000),
|
||||||
|
|
||||||
|
@ -1714,7 +1714,7 @@ void SLT_Transition::update()
|
||||||
// after airspeed is reached we degrade throttle over the
|
// after airspeed is reached we degrade throttle over the
|
||||||
// transition time, but continue to stabilize
|
// transition time, but continue to stabilize
|
||||||
const uint32_t transition_timer_ms = now - transition_low_airspeed_ms;
|
const uint32_t transition_timer_ms = now - transition_low_airspeed_ms;
|
||||||
const float trans_time_ms = constrain_float(quadplane.transition_time_ms,2000,30000);
|
const float trans_time_ms = constrain_float(quadplane.transition_time_ms,500,30000);
|
||||||
if (transition_timer_ms > unsigned(trans_time_ms)) {
|
if (transition_timer_ms > unsigned(trans_time_ms)) {
|
||||||
transition_state = TRANSITION_DONE;
|
transition_state = TRANSITION_DONE;
|
||||||
in_forced_transition = false;
|
in_forced_transition = false;
|
||||||
|
|
Loading…
Reference in New Issue