Skip to content

Commit d643e8f

Browse files
committed
AC_PID: add accessor to set ILMI
AC_PID: implement heli ILMI to constructor AC_PID: include ILMI in loading default params
1 parent bb7ebae commit d643e8f

3 files changed

Lines changed: 34 additions & 28 deletions

File tree

libraries/AC_PID/AC_HELI_PID.cpp

Lines changed: 27 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -8,29 +8,29 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = {
88
// @Param: P
99
// @DisplayName: PID Proportional Gain
1010
// @Description: P Gain which produces an output value that is proportional to the current error value
11-
AP_GROUPINFO("P", 0, AC_HELI_PID, _kp, 0),
11+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("P", 0, AC_HELI_PID, _kp, default_kp),
1212

1313
// @Param: I
1414
// @DisplayName: PID Integral Gain
1515
// @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error
16-
AP_GROUPINFO("I", 1, AC_HELI_PID, _ki, 0),
16+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("I", 1, AC_HELI_PID, _ki, default_ki),
1717

1818
// @Param: D
1919
// @DisplayName: PID Derivative Gain
2020
// @Description: D Gain which produces an output that is proportional to the rate of change of the error
21-
AP_GROUPINFO("D", 2, AC_HELI_PID, _kd, 0),
21+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D", 2, AC_HELI_PID, _kd, default_kd),
2222

2323
// 3 was for uint16 IMAX
2424

2525
// @Param: FF
2626
// @DisplayName: FF FeedForward Gain
2727
// @Description: FF Gain which produces an output value that is proportional to the demanded input
28-
AP_GROUPINFO("FF", 4, AC_HELI_PID, _kff, 0),
28+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FF", 4, AC_HELI_PID, _kff, default_kff),
2929

3030
// @Param: IMAX
3131
// @DisplayName: PID Integral Maximum
3232
// @Description: The maximum/minimum value that the I term can output
33-
AP_GROUPINFO("IMAX", 5, AC_HELI_PID, _kimax, 0),
33+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("IMAX", 5, AC_HELI_PID, _kimax, default_kimax),
3434

3535
// 6 was for float FILT
3636

@@ -39,35 +39,35 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = {
3939
// @Description: Point below which I-term will not leak down
4040
// @Range: 0 1
4141
// @User: Advanced
42-
AP_GROUPINFO("ILMI", 7, AC_HELI_PID, _leak_min, AC_PID_LEAK_MIN),
42+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("ILMI", 7, AC_HELI_PID, _leak_min, default_ilmi),
4343

4444
// 8 was for float AFF
4545

4646
// @Param: FLTT
4747
// @DisplayName: PID Target filter frequency in Hz
48-
// @Description: Target filter frequency in Hz
48+
// @Description: Low-pass filter frequency applied to the target input (Hz)
4949
// @Units: Hz
50-
AP_GROUPINFO("FLTT", 9, AC_HELI_PID, _filt_T_hz, AC_PID_TFILT_HZ_DEFAULT),
50+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FLTT", 9, AC_HELI_PID, _filt_T_hz, default_filt_T_hz),
5151

5252
// @Param: FLTE
5353
// @DisplayName: PID Error filter frequency in Hz
54-
// @Description: Error filter frequency in Hz
54+
// @Description: Low-pass filter frequency applied to the error (Hz)
5555
// @Units: Hz
56-
AP_GROUPINFO("FLTE", 10, AC_HELI_PID, _filt_E_hz, AC_PID_EFILT_HZ_DEFAULT),
56+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FLTE", 10, AC_HELI_PID, _filt_E_hz, default_filt_E_hz),
5757

5858
// @Param: FLTD
59-
// @DisplayName: PID D term filter frequency in Hz
60-
// @Description: Derivative filter frequency in Hz
59+
// @DisplayName: PID Derivative term filter frequency in Hz
60+
// @Description: Low-pass filter frequency applied to the derivative (Hz)
6161
// @Units: Hz
62-
AP_GROUPINFO("FLTD", 11, AC_HELI_PID, _filt_D_hz, AC_PID_DFILT_HZ_DEFAULT),
62+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FLTD", 11, AC_HELI_PID, _filt_D_hz, default_filt_D_hz),
6363

6464
// @Param: SMAX
6565
// @DisplayName: Slew rate limit
6666
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
6767
// @Range: 0 200
6868
// @Increment: 0.5
6969
// @User: Advanced
70-
AP_GROUPINFO("SMAX", 12, AC_HELI_PID, _slew_rate_max, 0),
70+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("SMAX", 12, AC_HELI_PID, _slew_rate_max, default_slew_rate_max),
7171

7272
// @Param: PDMX
7373
// @DisplayName: PD sum maximum
@@ -81,7 +81,7 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = {
8181
// @Range: 0 0.02
8282
// @Increment: 0.0001
8383
// @User: Advanced
84-
AP_GROUPINFO("D_FF", 14, AC_HELI_PID, _kdff, 0),
84+
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D_FF", 14, AC_HELI_PID, _kdff, default_kdff),
8585

8686
#if AP_FILTER_ENABLED
8787
// @Param: NTF
@@ -102,6 +102,18 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = {
102102
AP_GROUPEND
103103
};
104104

105+
// Constructor
106+
AC_HELI_PID::AC_HELI_PID(const AC_PID::Defaults &defaults, float initial_ilmi) :
107+
AC_PID{defaults},
108+
default_ilmi(initial_ilmi)
109+
{
110+
111+
// load parameter values from eeprom
112+
AP_Param::setup_object_defaults(this, var_info);
113+
114+
_last_requested_rate = 0;
115+
}
116+
105117
// This is an integrator which tends to decay to zero naturally
106118
// if the error is zero.
107119

libraries/AC_PID/AC_HELI_PID.h

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -9,29 +9,24 @@
99
#include <cmath>
1010
#include "AC_PID.h"
1111

12-
static const float AC_PID_LEAK_MIN = 0.1f; // Default I-term Leak Minimum
13-
1412
/// @class AC_HELI_PID
1513
/// @brief Heli PID control class
1614
class AC_HELI_PID : public AC_PID {
1715
public:
1816

19-
CLASS_NO_COPY(AC_HELI_PID);
17+
/// Constructor for PID controller with EEPROM-backed gain.
18+
/// Parameters are initialized from defaults or EEPROM at runtime.
19+
AC_HELI_PID(const AC_PID::Defaults &defaults, float initial_ilmi);
2020

21-
/// Constructor for PID
22-
AC_HELI_PID(const AC_PID::Defaults &defaults) :
23-
AC_PID{defaults}
24-
{
25-
_last_requested_rate = 0;
26-
}
21+
CLASS_NO_COPY(AC_HELI_PID);
2722

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

3126
static const struct AP_Param::GroupInfo var_info[];
3227

3328
private:
34-
AP_Float _leak_min;
35-
36-
float _last_requested_rate; // Requested rate from last iteration, used to calculate rate change of requested rate
29+
AP_Float _leak_min;
30+
float _last_requested_rate; // Requested rate from last iteration, used to calculate rate change of requested rate
31+
const float default_ilmi;
3732
};

libraries/AC_PID/AC_PID.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -203,7 +203,6 @@ class AC_PID {
203203

204204
AP_PIDInfo _pid_info;
205205

206-
private:
207206
const float default_kp;
208207
const float default_ki;
209208
const float default_kd;

0 commit comments

Comments
 (0)