APM:Libraries
AC_PID.h
Go to the documentation of this file.
1 #pragma once
2 
5 
6 #include <AP_Common/AP_Common.h>
7 #include <AP_Param/AP_Param.h>
8 #include <stdlib.h>
9 #include <cmath>
10 #include <DataFlash/DataFlash.h>
11 
12 #define AC_PID_FILT_HZ_DEFAULT 20.0f // default input filter frequency
13 #define AC_PID_FILT_HZ_MIN 0.01f // minimum input filter frequency
14 
17 class AC_PID {
18 public:
19 
20  // Constructor for PID
21  AC_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff = 0);
22 
23  // set_dt - set time step in seconds
24  void set_dt(float dt);
25 
26  // set_input_filter_all - set input to PID controller
27  // input is filtered before the PID controllers are run
28  // this should be called before any other calls to get_p, get_i or get_d
29  void set_input_filter_all(float input);
30 
31  // set_input_filter_d - set input to PID controller
32  // only input to the D portion of the controller is filtered
33  // this should be called before any other calls to get_p, get_i or get_d
34  void set_input_filter_d(float input);
35 
36  // get_pid - get results from pid controller
37  float get_pid();
38  float get_pi();
39  float get_p();
40  float get_i();
41  float get_d();
42  float get_ff(float requested_rate);
43 
44  // reset_I - reset the integrator
45  void reset_I();
46 
47  // reset_filter - input filter will be reset to the next value provided to set_input()
48  void reset_filter() { _flags._reset_filter = true; }
49 
50  // load gain from eeprom
51  void load_gains();
52 
53  // save gain to eeprom
54  void save_gains();
55 
57  void operator() (float p, float i, float d, float imaxval, float input_filt_hz, float dt, float ffval = 0);
58 
59  // get accessors
60  AP_Float &kP() { return _kp; }
61  AP_Float &kI() { return _ki; }
62  AP_Float &kD() { return _kd; }
63  AP_Float &filt_hz() { return _filt_hz; }
64  float imax() const { return _imax.get(); }
65  float get_filt_alpha() const;
66  float ff() const { return _ff.get(); }
67 
68  // set accessors
69  void kP(const float v) { _kp.set(v); }
70  void kI(const float v) { _ki.set(v); }
71  void kD(const float v) { _kd.set(v); }
72  void imax(const float v) { _imax.set(fabsf(v)); }
73  void filt_hz(const float v);
74  void ff(const float v) { _ff.set(v); }
75 
76  float get_integrator() const { return _integrator; }
77  void set_integrator(float i) { _integrator = i; }
78 
79  // set the designed rate (for logging purposes)
80  void set_desired_rate(float desired) { _pid_info.desired = desired; }
81 
82  const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; }
83 
84  // parameter var table
85  static const struct AP_Param::GroupInfo var_info[];
86 
87 protected:
88 
89  // parameters
90  AP_Float _kp;
91  AP_Float _ki;
92  AP_Float _kd;
93  AP_Float _imax;
94  AP_Float _filt_hz; // PID Input filter frequency in Hz
95  AP_Float _ff;
96 
97  // flags
98  struct ac_pid_flags {
99  bool _reset_filter : 1; // true when input filter should be reset during next call to set_input
100  } _flags;
101 
102  // internal variables
103  float _dt; // timestep in seconds
104  float _integrator; // integrator value
105  float _input; // last input for derivative
106  float _derivative; // last derivative for low-pass filter
107 
109 };
AP_Float _imax
Definition: AC_PID.h:93
void save_gains()
Definition: AC_PID.cpp:195
void kP(const float v)
Definition: AC_PID.h:69
float _integrator
Definition: AC_PID.h:104
struct AC_PID::ac_pid_flags _flags
AP_Float & filt_hz()
Definition: AC_PID.h:63
AC_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff=0)
Definition: AC_PID.cpp:46
AP_Float & kP()
Definition: AC_PID.h:60
void kD(const float v)
Definition: AC_PID.h:71
AP_Float _kp
Definition: AC_PID.h:90
float _derivative
Definition: AC_PID.h:106
void imax(const float v)
Definition: AC_PID.h:72
float get_d()
Definition: AC_PID.cpp:155
AP_Float _kd
Definition: AC_PID.h:92
float get_pi()
Definition: AC_PID.cpp:169
void reset_I()
Definition: AC_PID.cpp:179
void ff(const float v)
Definition: AC_PID.h:74
float _dt
Definition: AC_PID.h:103
void set_integrator(float i)
Definition: AC_PID.h:77
A system for managing and storing variables that are of general interest to the system.
float get_filt_alpha() const
Definition: AC_PID.cpp:217
void set_input_filter_d(float input)
Definition: AC_PID.cpp:112
float _input
Definition: AC_PID.h:105
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_PID.h:85
AP_Float _ki
Definition: AC_PID.h:91
float imax() const
Definition: AC_PID.h:64
float get_ff(float requested_rate)
Definition: AC_PID.cpp:162
const DataFlash_Class::PID_Info & get_pid_info(void) const
Definition: AC_PID.h:82
float v
Definition: Printf.cpp:15
AP_Float _ff
Definition: AC_PID.h:95
float ff() const
Definition: AC_PID.h:66
void set_desired_rate(float desired)
Definition: AC_PID.h:80
Common definitions and utility routines for the ArduPilot libraries.
void reset_filter()
Definition: AC_PID.h:48
void operator()(float p, float i, float d, float imaxval, float input_filt_hz, float dt, float ffval=0)
operator function call for easy initialisation
Definition: AC_PID.cpp:205
float get_pid()
Definition: AC_PID.cpp:174
void load_gains()
Definition: AC_PID.cpp:184
void set_dt(float dt)
Definition: AC_PID.cpp:69
void set_input_filter_all(float input)
Definition: AC_PID.cpp:87
AP_Float & kD()
Definition: AC_PID.h:62
AP_Float _filt_hz
Definition: AC_PID.h:94
float get_integrator() const
Definition: AC_PID.h:76
float get_i()
Definition: AC_PID.cpp:140
Copter PID control class.
Definition: AC_PID.h:17
void kI(const float v)
Definition: AC_PID.h:70
AP_Float & kI()
Definition: AC_PID.h:61
float get_p()
Definition: AC_PID.cpp:134
DataFlash_Class::PID_Info _pid_info
Definition: AC_PID.h:108