mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Motors: properly constrain thr_adj_max
This commit is contained in:
parent
9bf9e0ede9
commit
9959a44453
@ -250,7 +250,7 @@ void AP_MotorsMatrix::output_armed()
|
||||
thr_adj = _rc_throttle.radio_out - out_best_thr_pwm;
|
||||
|
||||
// calc upper and lower limits of thr_adj
|
||||
int16_t thr_adj_max = out_max_pwm-(out_best_thr_pwm+rpy_high);
|
||||
int16_t thr_adj_max = max(out_max_pwm-(out_best_thr_pwm+rpy_high),0);
|
||||
|
||||
// if we are increasing the throttle (situation #2 above)..
|
||||
if (thr_adj > 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user