mirror of https://github.com/ArduPilot/ardupilot
Plane: ensure speed scaling covers full aircraft speed range
this is important for very fast or very slow aircraft
This commit is contained in:
parent
bcd2d3805d
commit
1ed8e4fd2b
|
@ -17,7 +17,10 @@ float Plane::get_speed_scaler(void)
|
||||||
} else {
|
} else {
|
||||||
speed_scaler = 2.0;
|
speed_scaler = 2.0;
|
||||||
}
|
}
|
||||||
speed_scaler = constrain_float(speed_scaler, 0.5f, 2.0f);
|
// ensure we have scaling over the full configured airspeed
|
||||||
|
float scale_min = MIN(0.5, (0.5 * aparm.airspeed_min) / g.scaling_speed);
|
||||||
|
float scale_max = MAX(2.0, (1.5 * aparm.airspeed_max) / g.scaling_speed);
|
||||||
|
speed_scaler = constrain_float(speed_scaler, scale_min, scale_max);
|
||||||
|
|
||||||
if (quadplane.in_vtol_mode() && hal.util->get_soft_armed()) {
|
if (quadplane.in_vtol_mode() && hal.util->get_soft_armed()) {
|
||||||
// when in VTOL modes limit surface movement at low speed to prevent instability
|
// when in VTOL modes limit surface movement at low speed to prevent instability
|
||||||
|
|
Loading…
Reference in New Issue