APM:Libraries
PID.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Common/AP_Common.h>
6 #include <AP_Param/AP_Param.h>
7 #include <DataFlash/DataFlash.h>
8 #include <stdlib.h>
9 #include <cmath>
10 
13 class PID {
14 public:
15 
16  PID(const float & initial_p = 0.0f,
17  const float & initial_i = 0.0f,
18  const float & initial_d = 0.0f,
19  const int16_t & initial_imax = 0)
20  {
22  _kp = initial_p;
23  _ki = initial_i;
24  _kd = initial_d;
25  _imax = initial_imax;
26 
27  // set _last_derivative as invalid when we startup
28  _last_derivative = NAN;
29  }
30 
40  float get_pid(float error, float scaler = 1.0);
41 
43  //
44  void reset();
45 
48  void reset_I();
49 
52  void load_gains();
53 
56  void save_gains();
57 
59 
60 
62  void operator () (const float p,
63  const float i,
64  const float d,
65  const int16_t imaxval) {
66  _kp = p; _ki = i; _kd = d; _imax = imaxval;
67  }
68 
69  float kP() const {
70  return _kp.get();
71  }
72  float kI() const {
73  return _ki.get();
74  }
75  float kD() const {
76  return _kd.get();
77  }
78  int16_t imax() const {
79  return _imax.get();
80  }
81 
82  void kP(const float v) {
83  _kp.set(v);
84  }
85  void kI(const float v) {
86  _ki.set(v);
87  }
88  void kD(const float v) {
89  _kd.set(v);
90  }
91  void imax(const int16_t v) {
92  _imax.set(abs(v));
93  }
94 
95  float get_integrator() const {
96  return _integrator;
97  }
98 
99  static const struct AP_Param::GroupInfo var_info[];
100 
101  const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; }
102 
103 private:
104  AP_Float _kp;
105  AP_Float _ki;
106  AP_Float _kd;
107  AP_Int16 _imax;
108 
109  float _integrator;
110  float _last_error;
112  uint32_t _last_t;
113 
114  float _get_pid(float error, uint16_t dt, float scaler);
115 
117 
123  static const uint8_t _fCut = 20;
124 };
void load_gains()
Definition: PID.cpp:128
float kI() const
Definition: PID.h:72
AP_Float _kp
Definition: PID.h:104
void kD(const float v)
Definition: PID.h:88
float _integrator
integrator value
Definition: PID.h:109
static const uint8_t _fCut
Definition: PID.h:123
const DataFlash_Class::PID_Info & get_pid_info(void) const
Definition: PID.h:101
void save_gains()
Definition: PID.cpp:137
A system for managing and storing variables that are of general interest to the system.
float _get_pid(float error, uint16_t dt, float scaler)
int16_t imax() const
Definition: PID.h:78
#define f(i)
Object managing one PID control.
Definition: PID.h:13
void operator()(const float p, const float i, const float d, const int16_t imaxval)
Overload the function call operator to permit relatively easy initialisation.
Definition: PID.h:62
void reset()
Reset the whole PID state.
Definition: PID.cpp:122
float _last_error
last error for derivative
Definition: PID.h:110
DataFlash_Class::PID_Info _pid_info
Definition: PID.h:116
float v
Definition: Printf.cpp:15
PID(const float &initial_p=0.0f, const float &initial_i=0.0f, const float &initial_d=0.0f, const int16_t &initial_imax=0)
Definition: PID.h:16
float _last_derivative
last derivative for low-pass filter
Definition: PID.h:111
void kI(const float v)
Definition: PID.h:85
Common definitions and utility routines for the ArduPilot libraries.
void reset_I()
Definition: PID.cpp:113
AP_Int16 _imax
Definition: PID.h:107
float get_pid(float error, float scaler=1.0)
Definition: PID.cpp:37
AP_Float _kd
Definition: PID.h:106
#define error(fmt, args ...)
void imax(const int16_t v)
Definition: PID.h:91
void kP(const float v)
Definition: PID.h:82
uint32_t _last_t
last time get_pid() was called in millis
Definition: PID.h:112
float kP() const
Definition: PID.h:69
static const struct AP_Param::GroupInfo var_info[]
Definition: PID.h:99
AP_Float _ki
Definition: PID.h:105
float get_integrator() const
Definition: PID.h:95
float kD() const
Definition: PID.h:75
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214