AC_PosControl: accel_to_throttle outputs 0 to 1

This commit is contained in:
Leonard Hall 2015-12-20 22:03:29 +10:30 committed by Randy Mackay
parent e5d6d45851
commit 15be80a25d
1 changed files with 1 additions and 1 deletions

View File

@ -480,7 +480,7 @@ void AC_PosControl::accel_to_throttle(float accel_target_z)
// get d term
d = _pid_accel_z.get_d();
float thr_out = p+i+d+_throttle_hover;
float thr_out = (p+i+d)/1000.0f +_throttle_hover;
// send throttle to attitude controller with angle boost
_attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ);