mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Plane: correct extened range airspeed scailing limits
This commit is contained in:
parent
3610d36fce
commit
5a53e22886
@ -12,14 +12,14 @@ float Plane::calc_speed_scaler(void)
|
|||||||
if (aspeed > auto_state.highest_airspeed && hal.util->get_soft_armed()) {
|
if (aspeed > auto_state.highest_airspeed && hal.util->get_soft_armed()) {
|
||||||
auto_state.highest_airspeed = aspeed;
|
auto_state.highest_airspeed = aspeed;
|
||||||
}
|
}
|
||||||
|
// ensure we have scaling over the full configured airspeed
|
||||||
|
const float scale_min = MIN(0.5, g.scaling_speed / (2.0 * aparm.airspeed_max));
|
||||||
|
const float scale_max = MAX(2.0, g.scaling_speed / (0.7 * aparm.airspeed_min));
|
||||||
if (aspeed > 0.0001f) {
|
if (aspeed > 0.0001f) {
|
||||||
speed_scaler = g.scaling_speed / aspeed;
|
speed_scaler = g.scaling_speed / aspeed;
|
||||||
} else {
|
} else {
|
||||||
speed_scaler = 2.0;
|
speed_scaler = scale_max;
|
||||||
}
|
}
|
||||||
// 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);
|
speed_scaler = constrain_float(speed_scaler, scale_min, scale_max);
|
||||||
|
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user