APM:Libraries
Public Member Functions | List of all members
PID Class Reference

Object managing one PID control. More...

#include <PID.h>

Collaboration diagram for PID:
[legend]

Public Member Functions

 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)
 
float get_pid (float error, float scaler=1.0)
 
void reset ()
 Reset the whole PID state. More...
 
void reset_I ()
 
void load_gains ()
 
void save_gains ()
 

parameter accessors

static const struct AP_Param::GroupInfo var_info []
 
AP_Float _kp
 
AP_Float _ki
 
AP_Float _kd
 
AP_Int16 _imax
 
float _integrator
 integrator value More...
 
float _last_error
 last error for derivative More...
 
float _last_derivative
 last derivative for low-pass filter More...
 
uint32_t _last_t
 last time get_pid() was called in millis More...
 
DataFlash_Class::PID_Info _pid_info {}
 
static const uint8_t _fCut = 20
 
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. More...
 
float kP () const
 
float kI () const
 
float kD () const
 
int16_t imax () const
 
void kP (const float v)
 
void kI (const float v)
 
void kD (const float v)
 
void imax (const int16_t v)
 
float get_integrator () const
 
const DataFlash_Class::PID_Infoget_pid_info (void) const
 
float _get_pid (float error, uint16_t dt, float scaler)
 

Detailed Description

Object managing one PID control.

Definition at line 13 of file PID.h.

Constructor & Destructor Documentation

◆ PID()

PID::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 
)
inline

Definition at line 16 of file PID.h.

Here is the call graph for this function:

Member Function Documentation

◆ _get_pid()

float PID::_get_pid ( float  error,
uint16_t  dt,
float  scaler 
)
private

◆ get_integrator()

float PID::get_integrator ( ) const
inline

Definition at line 95 of file PID.h.

◆ get_pid()

float PID::get_pid ( float  error,
float  scaler = 1.0 
)

Iterate the PID, return the new control value

Positive error produces positive output.

Parameters
errorThe measured error value
scalerAn arbitrary scale factor
Returns
The updated control output.

Definition at line 37 of file PID.cpp.

Referenced by PID(), and AP_Landing_Deepstall::update_steering().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_pid_info()

const DataFlash_Class::PID_Info& PID::get_pid_info ( void  ) const
inline

Definition at line 101 of file PID.h.

Referenced by AP_Landing_Deepstall::get_pid_info(), and AP_Landing_Deepstall::Log().

Here is the caller graph for this function:

◆ imax() [1/2]

int16_t PID::imax ( ) const
inline

Definition at line 78 of file PID.h.

◆ imax() [2/2]

void PID::imax ( const int16_t  v)
inline

Definition at line 91 of file PID.h.

◆ kD() [1/2]

float PID::kD ( ) const
inline

Definition at line 75 of file PID.h.

◆ kD() [2/2]

void PID::kD ( const float  v)
inline

Definition at line 88 of file PID.h.

◆ kI() [1/2]

float PID::kI ( void  ) const
inline

Definition at line 72 of file PID.h.

◆ kI() [2/2]

void PID::kI ( const float  v)
inline

Definition at line 85 of file PID.h.

◆ kP() [1/2]

float PID::kP ( void  ) const
inline

Definition at line 69 of file PID.h.

◆ kP() [2/2]

void PID::kP ( const float  v)
inline

Definition at line 82 of file PID.h.

◆ load_gains()

void PID::load_gains ( )

Load gain properties

Definition at line 128 of file PID.cpp.

Referenced by PID().

Here is the caller graph for this function:

◆ operator()()

void PID::operator() ( const float  p,
const float  i,
const float  d,
const int16_t  imaxval 
)
inline

Overload the function call operator to permit relatively easy initialisation.

Definition at line 62 of file PID.h.

◆ reset()

void PID::reset ( void  )

Reset the whole PID state.

Definition at line 122 of file PID.cpp.

Referenced by AP_Landing_Deepstall::do_land(), PID(), and AP_Landing_Deepstall::terminate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ reset_I()

void PID::reset_I ( )

Reset the PID integrator

Definition at line 113 of file PID.cpp.

Referenced by get_pid(), PID(), and reset().

Here is the caller graph for this function:

◆ save_gains()

void PID::save_gains ( )

Save gain properties

Definition at line 137 of file PID.cpp.

Referenced by PID().

Here is the caller graph for this function:

Member Data Documentation

◆ _fCut

const uint8_t PID::_fCut = 20
staticprivate

Low pass filter cut frequency for derivative calculation.

20 Hz because anything over that is probably noise, see http://en.wikipedia.org/wiki/Low-pass_filter.

Definition at line 123 of file PID.h.

Referenced by get_pid().

◆ _imax

AP_Int16 PID::_imax
private

Definition at line 107 of file PID.h.

Referenced by get_pid(), imax(), load_gains(), operator()(), PID(), and save_gains().

◆ _integrator

float PID::_integrator
private

integrator value

Definition at line 109 of file PID.h.

Referenced by get_integrator(), get_pid(), and reset_I().

◆ _kd

AP_Float PID::_kd
private

Definition at line 106 of file PID.h.

Referenced by get_pid(), kD(), load_gains(), operator()(), PID(), and save_gains().

◆ _ki

AP_Float PID::_ki
private

Definition at line 105 of file PID.h.

Referenced by get_pid(), kI(), load_gains(), operator()(), PID(), and save_gains().

◆ _kp

AP_Float PID::_kp
private

Definition at line 104 of file PID.h.

Referenced by get_pid(), kP(), load_gains(), operator()(), PID(), and save_gains().

◆ _last_derivative

float PID::_last_derivative
private

last derivative for low-pass filter

Definition at line 111 of file PID.h.

Referenced by get_pid(), PID(), and reset_I().

◆ _last_error

float PID::_last_error
private

last error for derivative

Definition at line 110 of file PID.h.

Referenced by get_pid().

◆ _last_t

uint32_t PID::_last_t
private

last time get_pid() was called in millis

Definition at line 112 of file PID.h.

Referenced by get_pid().

◆ _pid_info

DataFlash_Class::PID_Info PID::_pid_info {}
private

Definition at line 116 of file PID.h.

Referenced by get_pid(), get_pid_info(), reset(), and reset_I().

◆ var_info

const AP_Param::GroupInfo PID::var_info
static
Initial value:
= {
AP_GROUPINFO("P", 0, PID, _kp, 0),
AP_GROUPINFO("I", 1, PID, _ki, 0),
AP_GROUPINFO("D", 2, PID, _kd, 0),
AP_GROUPINFO("IMAX", 3, PID, _imax, 0),
}

Definition at line 99 of file PID.h.

Referenced by PID().


The documentation for this class was generated from the following files: