mirror of https://github.com/ArduPilot/ardupilot
Heli: Prevent loss of yaw control during large angle recovery
This commit is contained in:
parent
5ef676e40c
commit
b84078d396
|
@ -358,7 +358,7 @@ float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_ra
|
||||||
float pid = _pid_rate_yaw.update_all(rate_target_rads, rate_yaw_actual_rads, _flags_heli.limit_yaw) + _actuator_sysid.z;
|
float pid = _pid_rate_yaw.update_all(rate_target_rads, rate_yaw_actual_rads, _flags_heli.limit_yaw) + _actuator_sysid.z;
|
||||||
|
|
||||||
// use pid library to calculate ff
|
// use pid library to calculate ff
|
||||||
float vff = _pid_rate_yaw.get_ff();
|
float vff = _pid_rate_yaw.get_ff()*_feedforward_scalar;
|
||||||
|
|
||||||
// add feed forward
|
// add feed forward
|
||||||
float yaw_out = pid + vff;
|
float yaw_out = pid + vff;
|
||||||
|
|
Loading…
Reference in New Issue