mirror of https://github.com/ArduPilot/ardupilot
AC_AttitudeControl: removed use of AFF for tail control in heli
This commit is contained in:
parent
a6404cf1ea
commit
9bf0ada875
|
@ -351,7 +351,7 @@ void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(float rate_roll_target
|
|||
// rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
|
||||
float AC_AttitudeControl_Heli::rate_bf_to_motor_yaw(float rate_target_rads)
|
||||
{
|
||||
float pd,i,vff,aff; // used to capture pid values for logging
|
||||
float pd,i,vff; // used to capture pid values for logging
|
||||
float current_rate_rads; // this iteration's rate
|
||||
float rate_error_rads; // simply target_rate - current_rate
|
||||
float yaw_out;
|
||||
|
@ -384,10 +384,9 @@ float AC_AttitudeControl_Heli::rate_bf_to_motor_yaw(float rate_target_rads)
|
|||
|
||||
// For legacy reasons, we convert to centi-degrees before inputting to the feedforward
|
||||
vff = yaw_velocity_feedforward_filter.apply(_pid_rate_yaw.get_vff(rate_target_rads), _dt);
|
||||
aff = yaw_acceleration_feedforward_filter.apply(_pid_rate_yaw.get_aff(rate_target_rads), _dt);
|
||||
|
||||
// add feed forward
|
||||
yaw_out = pd + i + vff + aff;
|
||||
yaw_out = pd + i + vff;
|
||||
|
||||
// constrain output and update limit flag
|
||||
if (fabsf(yaw_out) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX) {
|
||||
|
|
|
@ -26,7 +26,6 @@
|
|||
#define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE 0.02f
|
||||
#define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 10.0f
|
||||
#define AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER 10.0f
|
||||
#define AC_ATTITUDE_HELI_RATE_Y_AFF_FILTER 10.0f
|
||||
#define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT 300
|
||||
|
||||
class AC_AttitudeControl_Heli : public AC_AttitudeControl {
|
||||
|
@ -42,8 +41,7 @@ public:
|
|||
_pid_rate_yaw(AC_ATC_HELI_RATE_YAW_P, AC_ATC_HELI_RATE_YAW_I, AC_ATC_HELI_RATE_YAW_D, AC_ATC_HELI_RATE_YAW_IMAX, AC_ATC_HELI_RATE_YAW_FILT_HZ, dt, AC_ATC_HELI_RATE_YAW_FF),
|
||||
pitch_feedforward_filter(AC_ATTITUDE_HELI_RATE_RP_FF_FILTER),
|
||||
roll_feedforward_filter(AC_ATTITUDE_HELI_RATE_RP_FF_FILTER),
|
||||
yaw_velocity_feedforward_filter(AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER),
|
||||
yaw_acceleration_feedforward_filter(AC_ATTITUDE_HELI_RATE_Y_AFF_FILTER)
|
||||
yaw_velocity_feedforward_filter(AC_ATTITUDE_HELI_RATE_Y_VFF_FILTER)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
|
|
Loading…
Reference in New Issue