mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: added speed scaling reduction for Q modes
when in a Q mode reduce surface movements at low airspeed, in case we have the wind from behind us. This prevents the control surfaces from causing instability
This commit is contained in:
parent
820b2386c0
commit
102ee99802
@ -18,6 +18,15 @@ float Plane::get_speed_scaler(void)
|
|||||||
speed_scaler = 2.0;
|
speed_scaler = 2.0;
|
||||||
}
|
}
|
||||||
speed_scaler = constrain_float(speed_scaler, 0.5f, 2.0f);
|
speed_scaler = constrain_float(speed_scaler, 0.5f, 2.0f);
|
||||||
|
|
||||||
|
if (quadplane.in_vtol_mode() && hal.util->get_soft_armed()) {
|
||||||
|
// when in VTOL modes limit surface movement at low speed to prevent instability
|
||||||
|
float threshold = aparm.airspeed_min * 0.5;
|
||||||
|
if (aspeed < threshold) {
|
||||||
|
float new_scaler = linear_interpolate(0, g.scaling_speed / threshold, aspeed, 0, threshold);
|
||||||
|
speed_scaler = MIN(speed_scaler, new_scaler);
|
||||||
|
}
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
if (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > 0) {
|
if (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > 0) {
|
||||||
speed_scaler = 0.5f + ((float)THROTTLE_CRUISE / SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) / 2.0f); // First order taylor expansion of square root
|
speed_scaler = 0.5f + ((float)THROTTLE_CRUISE / SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) / 2.0f); // First order taylor expansion of square root
|
||||||
|
Loading…
Reference in New Issue
Block a user