AC_PID: AC_HELI_PID: override the AC_PID::Default constructor

in place of the existing ordered-fields constructor
This commit is contained in:
Peter Barker 2024-09-20 17:19:00 +10:00 committed by Andrew Tridgell
parent 4663382b01
commit 17f501eea5
2 changed files with 7 additions and 10 deletions

View File

@ -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.

View File

@ -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);