APM:Libraries
AC_PI_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 
11 #define AC_PI_2D_FILT_HZ_DEFAULT 20.0f // default input filter frequency
12 #define AC_PI_2D_FILT_HZ_MIN 0.01f // minimum input filter frequency
13 
16 class AC_PI_2D {
17 public:
18 
19  // Constructor for PID
20  AC_PI_2D(float initial_p, float initial_i, float initial_imax, float initial_filt_hz, float dt);
21 
22  // set_dt - set time step in seconds
23  void set_dt(float dt);
24 
25  // set_input - set input to PID controller
26  // input is filtered before the PID controllers are run
27  // this should be called before any other calls to get_p, get_i or get_d
28  void set_input(const Vector2f &input);
29  void set_input(const Vector3f &input) { set_input(Vector2f(input.x, input.y)); }
30 
31  // get_pi - get results from pid controller
32  Vector2f get_pi();
33  Vector2f get_p() const;
34  Vector2f get_i();
35  Vector2f get_i_shrink(); // get_i but do not allow integrator to grow (it may shrink)
36 
37  // reset_I - reset the integrator
38  void reset_I();
39 
40  // reset_filter - input filter will be reset to the next value provided to set_input()
41  void reset_filter();
42 
43  // load gain from eeprom
44  void load_gains();
45 
46  // save gain to eeprom
47  void save_gains();
48 
50  void operator() (float p, float i, float imaxval, float input_filt_hz, float dt);
51 
52  // get accessors
53  AP_Float &kP() { return _kp; }
54  AP_Float &kI() { return _ki; }
55  float imax() const { return _imax.get(); }
56  float filt_hz() const { return _filt_hz.get(); }
57  float get_filt_alpha() const { return _filt_alpha; }
58 
59  // set accessors
60  void kP(const float v) { _kp.set(v); }
61  void kI(const float v) { _ki.set(v); }
62  void imax(const float v) { _imax.set(fabsf(v)); }
63  void filt_hz(const float v);
64 
65  Vector2f get_integrator() const { return _integrator; }
66  void set_integrator(const Vector2f &i) { _integrator = i; }
67  void set_integrator(const Vector3f &i) { _integrator.x = i.x; _integrator.y = i.y; }
68 
69  // parameter var table
70  static const struct AP_Param::GroupInfo var_info[];
71 
72 protected:
73 
74  // calc_filt_alpha - recalculate the input filter alpha
75  void calc_filt_alpha();
76 
77  // parameters
78  AP_Float _kp;
79  AP_Float _ki;
80  AP_Float _imax;
81  AP_Float _filt_hz; // PID Input filter frequency in Hz
82 
83  // flags
84  struct ac_pid_flags {
85  bool _reset_filter : 1; // true when input filter should be reset during next call to set_input
86  } _flags;
87 
88  // internal variables
89  float _dt; // timestep in seconds
90  Vector2f _integrator; // integrator value
91  Vector2f _input; // last input for derivative
92  float _filt_alpha; // input filter alpha
93 };
Vector2< float > Vector2f
Definition: vector2.h:239
Vector2f get_i()
Definition: AC_PI_2D.cpp:94
Vector2f get_i_shrink()
Definition: AC_PI_2D.cpp:108
Vector2f _input
Definition: AC_PI_2D.h:91
AP_Float _imax
Definition: AC_PI_2D.h:80
void set_input(const Vector3f &input)
Definition: AC_PI_2D.h:29
void save_gains()
Definition: AC_PI_2D.cpp:145
AP_Float _ki
Definition: AC_PI_2D.h:79
float _filt_alpha
Definition: AC_PI_2D.h:92
float filt_hz() const
Definition: AC_PI_2D.h:56
void load_gains()
Definition: AC_PI_2D.cpp:132
AP_Float _filt_hz
Definition: AC_PI_2D.h:81
void set_integrator(const Vector3f &i)
Definition: AC_PI_2D.h:67
void reset_filter()
A system for managing and storing variables that are of general interest to the system.
T y
Definition: vector2.h:37
Copter PID control class.
Definition: AC_PI_2D.h:16
void set_dt(float dt)
Definition: AC_PI_2D.cpp:49
float get_filt_alpha() const
Definition: AC_PI_2D.h:57
AP_Float & kI()
Definition: AC_PI_2D.h:54
T y
Definition: vector3.h:67
float _dt
Definition: AC_PI_2D.h:89
Vector2f get_integrator() const
Definition: AC_PI_2D.h:65
void kI(const float v)
Definition: AC_PI_2D.h:61
void imax(const float v)
Definition: AC_PI_2D.h:62
float v
Definition: Printf.cpp:15
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_PI_2D.h:70
void set_integrator(const Vector2f &i)
Definition: AC_PI_2D.h:66
void operator()(float p, float i, float imaxval, float input_filt_hz, float dt)
operator function call for easy initialisation
Definition: AC_PI_2D.cpp:154
AP_Float _kp
Definition: AC_PI_2D.h:78
float imax() const
Definition: AC_PI_2D.h:55
void reset_I()
Definition: AC_PI_2D.cpp:127
Common definitions and utility routines for the ArduPilot libraries.
T x
Definition: vector2.h:37
void set_input(const Vector2f &input)
Definition: AC_PI_2D.cpp:71
void calc_filt_alpha()
Definition: AC_PI_2D.cpp:166
void kP(const float v)
Definition: AC_PI_2D.h:60
Vector2f get_pi()
Definition: AC_PI_2D.cpp:122
AP_Float & kP()
Definition: AC_PI_2D.h:53
Vector2f _integrator
Definition: AC_PI_2D.h:90
struct AC_PI_2D::ac_pid_flags _flags
AC_PI_2D(float initial_p, float initial_i, float initial_imax, float initial_filt_hz, float dt)
Definition: AC_PI_2D.cpp:33
T x
Definition: vector3.h:67
Vector2f get_p() const
Definition: AC_PI_2D.cpp:89