mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: constrain throttle in NAV_SCRIPT
This commit is contained in:
parent
210dac7356
commit
06edc9a139
@ -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.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.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.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();
|
nav_scripting.current_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user