Browse Source

AC_PosControl: accel_to_throttle outputs 0 to 1

mission-4.1.18
Leonard Hall 9 years ago committed by Randy Mackay
parent
commit
15be80a25d
  1. 2
      libraries/AC_AttitudeControl/AC_PosControl.cpp

2
libraries/AC_AttitudeControl/AC_PosControl.cpp

@ -480,7 +480,7 @@ void AC_PosControl::accel_to_throttle(float accel_target_z) @@ -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);

Loading…
Cancel
Save