APM:Libraries
AC_HELI_PID.cpp
Go to the documentation of this file.
1 
4 #include <AP_Math/AP_Math.h>
5 #include "AC_HELI_PID.h"
6 
8  // @Param: P
9  // @DisplayName: PID Proportional Gain
10  // @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),
12 
13  // @Param: I
14  // @DisplayName: PID Integral Gain
15  // @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),
17 
18  // @Param: D
19  // @DisplayName: PID Derivative Gain
20  // @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),
22 
23  // @Param: VFF
24  // @DisplayName: Velocity FF FeedForward Gain
25  // @Description: Velocity FF Gain which produces an output value that is proportional to the demanded input
26  AP_GROUPINFO("VFF", 4, AC_HELI_PID, _ff, 0),
27 
28  // @Param: IMAX
29  // @DisplayName: PID Integral Maximum
30  // @Description: The maximum/minimum value that the I term can output
31  AP_GROUPINFO("IMAX", 5, AC_HELI_PID, _imax, 0),
32 
33  // @Param: FILT
34  // @DisplayName: PID Input filter frequency in Hz
35  // @Description: PID Input filter frequency in Hz
36  AP_GROUPINFO("FILT", 6, AC_HELI_PID, _filt_hz, AC_PID_FILT_HZ_DEFAULT),
37 
38  // @Param: ILMI
39  // @DisplayName: I-term Leak Minimum
40  // @Description: Point below which I-term will not leak down
41  // @Range: 0 1
42  // @User: Advanced
43  AP_GROUPINFO("ILMI", 7, AC_HELI_PID, _leak_min, AC_PID_LEAK_MIN),
44 
45  // index 8 was for AFF, now removed
46 
48 };
49 
51 AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff) :
52  AC_PID(initial_p, initial_i, initial_d, initial_imax, initial_filt_hz, dt, initial_ff)
53 {
55 }
56 
57 // This is an integrator which tends to decay to zero naturally
58 // if the error is zero.
59 
60 float AC_HELI_PID::get_leaky_i(float leak_rate)
61 {
62  if(!is_zero(_ki) && !is_zero(_dt)){
63 
64  // integrator does not leak down below Leak Min
65  if (_integrator > _leak_min){
66  _integrator -= (float)(_integrator - _leak_min) * leak_rate;
67  } else if (_integrator < -_leak_min) {
68  _integrator -= (float)(_integrator + _leak_min) * leak_rate;
69  }
70 
71  _integrator += ((float)_input * _ki) * _dt;
72  if (_integrator < -_imax) {
73  _integrator = -_imax;
74  } else if (_integrator > _imax) {
76  }
77 
79  return _integrator;
80  }
81  return 0;
82 }
AP_Float _imax
Definition: AC_PID.h:93
float _integrator
Definition: AC_PID.h:104
float _last_requested_rate
Definition: AC_HELI_PID.h:30
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float get_leaky_i(float leak_rate)
get_leaky_i - replacement for get_i but output is leaded at leak_rate
Definition: AC_HELI_PID.cpp:60
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_HELI_PID.h:25
float _dt
Definition: AC_PID.h:103
AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff)
Constructor for PID.
Definition: AC_HELI_PID.cpp:51
Heli PID control class.
Definition: AC_HELI_PID.h:16
Helicopter Specific Rate PID algorithm, with EEPROM-backed storage of constants.
float _input
Definition: AC_PID.h:105
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
AP_Float _ki
Definition: AC_PID.h:91
AP_Float _leak_min
Definition: AC_HELI_PID.h:28
#define AC_PID_FILT_HZ_DEFAULT
Definition: AC_PID.h:12
#define AC_PID_LEAK_MIN
Definition: AC_HELI_PID.h:12
Copter PID control class.
Definition: AC_PID.h:17
#define AP_GROUPEND
Definition: AP_Param.h:121
DataFlash_Class::PID_Info _pid_info
Definition: AC_PID.h:108