Plane: constrain throttle in NAV_SCRIPT

This commit is contained in:
Andrew Tridgell 2022-10-27 08:55:10 +11:00
parent 210dac7356
commit 06edc9a139
1 changed files with 1 additions and 1 deletions

View File

@ -1226,7 +1226,7 @@ void Plane::set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps
nav_scripting.roll_rate_dps = constrain_float(roll_rate_dps, -g.acro_roll_rate, g.acro_roll_rate);
nav_scripting.pitch_rate_dps = constrain_float(pitch_rate_dps, -g.acro_pitch_rate, g.acro_pitch_rate);
nav_scripting.yaw_rate_dps = constrain_float(yaw_rate_dps, -g.acro_yaw_rate, g.acro_yaw_rate);
nav_scripting.throttle_pct = throttle_pct;
nav_scripting.throttle_pct = constrain_float(throttle_pct, aparm.throttle_min, aparm.throttle_max);
nav_scripting.current_ms = AP_HAL::millis();
}