mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
AC_PosControl: ensure throttle output above zero
This commit is contained in:
parent
31a55b2bd6
commit
9a3f48cc1f
@ -380,8 +380,11 @@ void AC_PosControl::accel_to_throttle(float accel_target_z)
|
||||
// get d term
|
||||
d = _pid_accel_z.get_d();
|
||||
|
||||
// ensure throttle is above zero (or motors lib will stop stabilizing)
|
||||
int16_t thr_out = max((int16_t)p+i+d+_throttle_hover,1);
|
||||
|
||||
// send throttle to attitude controller with angle boost
|
||||
_attitude_control.set_throttle_out((int16_t)p+i+d+_throttle_hover, true);
|
||||
_attitude_control.set_throttle_out(thr_out, true);
|
||||
}
|
||||
|
||||
///
|
||||
|
Loading…
Reference in New Issue
Block a user