Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AC_AttitudeControl: use AC_PID defaults to tidy heli rate PID initialisers #28162

Merged
merged 2 commits into from
Sep 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 1 addition & 4 deletions libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -307,10 +307,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
};

AC_AttitudeControl_Heli::AC_AttitudeControl_Heli(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsHeli& motors) :
AC_AttitudeControl(ahrs, aparm, motors),
_pid_rate_roll(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f),
_pid_rate_pitch(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f),
_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_FF, AC_ATC_HELI_RATE_YAW_IMAX, AC_ATTITUDE_HELI_RATE_Y_FF_FILTER, AC_ATC_HELI_RATE_YAW_FILT_HZ, 0.0f)
AC_AttitudeControl(ahrs, aparm, motors)
{
AP_Param::setup_object_defaults(this, var_info);

Expand Down
36 changes: 33 additions & 3 deletions libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h
Original file line number Diff line number Diff line change
Expand Up @@ -150,8 +150,38 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl {
// parameters
AP_Int8 _piro_comp_enabled; // Flybar present or not. Affects attitude controller used during ACRO flight mode
AP_Int16 _hover_roll_trim; // Angle in centi-degrees used to counter tail rotor thrust in hover
AC_HELI_PID _pid_rate_roll;
AC_HELI_PID _pid_rate_pitch;
AC_HELI_PID _pid_rate_yaw;

// Roll and Pitch rate PIDs share the same defaults:
const AC_PID::Defaults rp_defaults {
AC_PID::Defaults{
.p = AC_ATC_HELI_RATE_RP_P,
.i = AC_ATC_HELI_RATE_RP_I,
.d = AC_ATC_HELI_RATE_RP_D,
.ff = AC_ATC_HELI_RATE_RP_FF,
.imax = AC_ATC_HELI_RATE_RP_IMAX,
.filt_T_hz = AC_ATTITUDE_HELI_RATE_RP_FF_FILTER,
.filt_E_hz = AC_ATC_HELI_RATE_RP_FILT_HZ,
.filt_D_hz = 0.0,
.srmax = 0,
.srtau = 1.0
}
};
AC_HELI_PID _pid_rate_roll { rp_defaults };
AC_HELI_PID _pid_rate_pitch { rp_defaults };

AC_HELI_PID _pid_rate_yaw {
AC_PID::Defaults{
.p = AC_ATC_HELI_RATE_YAW_P,
.i = AC_ATC_HELI_RATE_YAW_I,
.d = AC_ATC_HELI_RATE_YAW_D,
.ff = AC_ATC_HELI_RATE_YAW_FF,
.imax = AC_ATC_HELI_RATE_YAW_IMAX,
.filt_T_hz = AC_ATTITUDE_HELI_RATE_Y_FF_FILTER,
.filt_E_hz = AC_ATC_HELI_RATE_YAW_FILT_HZ,
.filt_D_hz = 0.0,
.srmax = 0,
.srtau = 1.0
}
};

};
7 changes: 0 additions & 7 deletions libraries/AC_PID/AC_HELI_PID.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,13 +102,6 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = {
AP_GROUPEND
};

/// Constructor for PID
AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float dff_val) :
AC_PID(initial_p, initial_i, initial_d, initial_ff, initial_imax, initial_filt_T_hz, initial_filt_E_hz, initial_filt_D_hz, dff_val)
{
_last_requested_rate = 0;
}

// This is an integrator which tends to decay to zero naturally
// if the error is zero.

Expand Down
10 changes: 7 additions & 3 deletions libraries/AC_PID/AC_HELI_PID.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,15 @@ static const float AC_PID_LEAK_MIN = 0.1f; // Default I-term Leak Minimum
class AC_HELI_PID : public AC_PID {
public:

/// Constructor for PID
AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float dff_val=0);

CLASS_NO_COPY(AC_HELI_PID);

/// Constructor for PID
AC_HELI_PID(const AC_PID::Defaults &defaults) :
AC_PID{defaults}
{
_last_requested_rate = 0;
}

/// update_leaky_i - replacement for get_i but output is leaked at leak_rate
void update_leaky_i(float leak_rate);

Expand Down
Loading