|
|
@ -480,7 +480,7 @@ void AC_PosControl::accel_to_throttle(float accel_target_z) |
|
|
|
// get d term
|
|
|
|
// get d term
|
|
|
|
d = _pid_accel_z.get_d(); |
|
|
|
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
|
|
|
|
// send throttle to attitude controller with angle boost
|
|
|
|
_attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ); |
|
|
|
_attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ); |
|
|
|