APM:Libraries
AC_PID_2D.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 
13 class AC_PID_2D {
14 public:
15 
16  // Constructor for PID
17  AC_PID_2D(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float initial_filt_d_hz, float dt);
18 
19  // set_dt - set time step in seconds
20  void set_dt(float dt);
21 
22  // set_input - set input to PID controller
23  // input is filtered before the PID controllers are run
24  // this should be called before any other calls to get_p, get_i or get_d
25  void set_input(const Vector2f &input);
26  void set_input(const Vector3f &input) { set_input(Vector2f(input.x, input.y)); }
27 
28  // get_pi - get results from pid controller
29  Vector2f get_pid();
30  Vector2f get_p() const;
31  Vector2f get_i();
32  Vector2f get_i_shrink(); // get_i but do not allow integrator to grow (it may shrink)
33  Vector2f get_d();
34 
35  // reset_I - reset the integrator
36  void reset_I();
37 
38  // reset_filter - input and D term filter will be reset to the next value provided to set_input()
39  void reset_filter();
40 
41  // load gain from eeprom
42  void load_gains();
43 
44  // save gain to eeprom
45  void save_gains();
46 
47  // get accessors
48  AP_Float &kP() { return _kp; }
49  AP_Float &kI() { return _ki; }
50  float imax() const { return _imax.get(); }
51  float filt_hz() const { return _filt_hz.get(); }
52  float get_filt_alpha() const { return _filt_alpha; }
53  float filt_d_hz() const { return _filt_hz.get(); }
54  float get_filt_alpha_D() const { return _filt_alpha_d; }
55 
56  // set accessors
57  void kP(const float v) { _kp.set(v); }
58  void kI(const float v) { _ki.set(v); }
59  void kD(const float v) { _kd.set(v); }
60  void imax(const float v) { _imax.set(fabsf(v)); }
61  void filt_hz(const float v);
62  void filt_d_hz(const float v);
63 
64  Vector2f get_integrator() const { return _integrator; }
65  void set_integrator(const Vector2f &i) { _integrator = i; }
66  void set_integrator(const Vector3f &i) { _integrator.x = i.x; _integrator.y = i.y; }
67 
68  // parameter var table
69  static const struct AP_Param::GroupInfo var_info[];
70 
71 protected:
72 
73  // set_input_filter_d - set input to PID controller
74  // only input to the D portion of the controller is filtered
75  // this should be called before any other calls to get_p, get_i or get_d
76  void set_input_filter_d(const Vector2f& input_delta);
77 
78  // calc_filt_alpha - recalculate the input filter alpha
79  void calc_filt_alpha();
80 
81  // calc_filt_alpha - recalculate the input filter alpha
82  void calc_filt_alpha_d();
83 
84  // parameters
85  AP_Float _kp;
86  AP_Float _ki;
87  AP_Float _kd;
88  AP_Float _imax;
89  AP_Float _filt_hz; // PID Input filter frequency in Hz
90  AP_Float _filt_d_hz; // D term filter frequency in Hz
91 
92  // flags
93  struct ac_pid_flags {
94  bool _reset_filter : 1; // true when input filter should be reset during next call to set_input
95  } _flags;
96 
97  // internal variables
98  float _dt; // timestep in seconds
99  float _filt_alpha; // input filter alpha
100  float _filt_alpha_d; // input filter alpha
101  Vector2f _integrator; // integrator value
102  Vector2f _input; // last input for derivative
103  Vector2f _derivative; // last derivative for low-pass filter
104 };
AP_Float _kp
Definition: AC_PID_2D.h:85
Vector2< float > Vector2f
Definition: vector2.h:239
void set_integrator(const Vector2f &i)
Definition: AC_PID_2D.h:65
Vector2f _derivative
Definition: AC_PID_2D.h:103
float filt_d_hz() const
Definition: AC_PID_2D.h:53
float get_filt_alpha_D() const
Definition: AC_PID_2D.h:54
Vector2f get_p() const
Definition: AC_PID_2D.cpp:147
void set_input(const Vector2f &input)
Definition: AC_PID_2D.cpp:102
Vector2f _integrator
Definition: AC_PID_2D.h:101
void kP(const float v)
Definition: AC_PID_2D.h:57
AP_Float _filt_d_hz
Definition: AC_PID_2D.h:90
void calc_filt_alpha()
Definition: AC_PID_2D.cpp:223
void set_integrator(const Vector3f &i)
Definition: AC_PID_2D.h:66
AC_PID_2D(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float initial_filt_d_hz, float dt)
Definition: AC_PID_2D.cpp:49
float _filt_alpha
Definition: AC_PID_2D.h:99
Vector2f get_integrator() const
Definition: AC_PID_2D.h:64
AP_Float _imax
Definition: AC_PID_2D.h:88
AP_Float & kP()
Definition: AC_PID_2D.h:48
Vector2f get_d()
Definition: AC_PID_2D.cpp:180
AP_Float & kI()
Definition: AC_PID_2D.h:49
void kD(const float v)
Definition: AC_PID_2D.h:59
A system for managing and storing variables that are of general interest to the system.
T y
Definition: vector2.h:37
float get_filt_alpha() const
Definition: AC_PID_2D.h:52
Vector2f get_i_shrink()
Definition: AC_PID_2D.cpp:166
void set_dt(float dt)
Definition: AC_PID_2D.cpp:67
Vector2f _input
Definition: AC_PID_2D.h:102
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_PID_2D.h:69
float filt_hz() const
Definition: AC_PID_2D.h:51
float imax() const
Definition: AC_PID_2D.h:50
T y
Definition: vector3.h:67
void set_input_filter_d(const Vector2f &input_delta)
Definition: AC_PID_2D.cpp:125
AP_Float _kd
Definition: AC_PID_2D.h:87
void reset_I()
Definition: AC_PID_2D.cpp:191
void calc_filt_alpha_d()
Definition: AC_PID_2D.cpp:236
void load_gains()
Definition: AC_PID_2D.cpp:196
float v
Definition: Printf.cpp:15
Vector2f get_pid()
Definition: AC_PID_2D.cpp:186
float _dt
Definition: AC_PID_2D.h:98
Vector2f get_i()
Definition: AC_PID_2D.cpp:152
Common definitions and utility routines for the ArduPilot libraries.
T x
Definition: vector2.h:37
Copter PID control class.
Definition: AC_PID_2D.h:13
AP_Float _ki
Definition: AC_PID_2D.h:86
void set_input(const Vector3f &input)
Definition: AC_PID_2D.h:26
AP_Float _filt_hz
Definition: AC_PID_2D.h:89
void imax(const float v)
Definition: AC_PID_2D.h:60
void kI(const float v)
Definition: AC_PID_2D.h:58
void save_gains()
Definition: AC_PID_2D.cpp:212
float _filt_alpha_d
Definition: AC_PID_2D.h:100
struct AC_PID_2D::ac_pid_flags _flags
void reset_filter()
T x
Definition: vector3.h:67