Public Member Functions | Protected Member Functions | Protected Attributes
Pid Class Reference

PID (Proportional, Integral, Derivative) control output. More...

#include <pid2.h>

List of all members.

Public Member Functions

void Clear ()
 Clears the integral term if the setpoint has been reached.
virtual void Configure (float kp, float ki, float kd)
 Configure PID gains.
virtual void Configure (float kp, float ki, float kd, float omax, float omin, float C)
 Configure all PID parameters.
virtual void Configure (const ros::NodeHandle &node)
 Configure PID parameters.
void CopyHistory (const Pid *pid)
 Copy the error history from another PID.
 Pid (const char *ctlname)
 Constructor.
 Pid (const char *ctlname, float kp, float ki, float kd, float omax=FLT_MAX, float omin=-FLT_MAX, float C=0.0)
float Update (float error, float output)
 Update PID control output.
virtual ~Pid ()

Protected Member Functions

void CfgParam (const ros::NodeHandle &node, const char *pname, float *fvalue)
 Configure one PID parameter.

Protected Attributes

float C
float dstate
float istate
float kd
float ki
float kp
std::string name
float omax
float omin
bool starting

Detailed Description

PID (Proportional, Integral, Derivative) control output.

Definition at line 23 of file pid2.h.


Constructor & Destructor Documentation

Pid::Pid ( const char *  ctlname) [inline]

Constructor.

Parameters:
ctlnamecontrol output name for log messages

Definition at line 30 of file pid2.h.

Pid::Pid ( const char *  ctlname,
float  kp,
float  ki,
float  kd,
float  omax = FLT_MAX,
float  omin = -FLT_MAX,
float  C = 0.0 
) [inline]

Definition at line 37 of file pid2.h.

virtual Pid::~Pid ( ) [inline, virtual]

Definition at line 45 of file pid2.h.


Member Function Documentation

void Pid::CfgParam ( const ros::NodeHandle node,
const char *  pname,
float *  fvalue 
) [inline, protected]

Configure one PID parameter.

Parameters:
nodenode handle for parameter server
pnamebase name for this parameter
fvalueplace to store parameter value, if defined (already set to default value).

Definition at line 181 of file pid2.h.

void Pid::Clear ( ) [inline]

Clears the integral term if the setpoint has been reached.

Definition at line 139 of file pid2.h.

virtual void Pid::Configure ( float  kp,
float  ki,
float  kd 
) [inline, virtual]

Configure PID gains.

Definition at line 48 of file pid2.h.

virtual void Pid::Configure ( float  kp,
float  ki,
float  kd,
float  omax,
float  omin,
float  C 
) [inline, virtual]

Configure all PID parameters.

Definition at line 56 of file pid2.h.

virtual void Pid::Configure ( const ros::NodeHandle node) [inline, virtual]

Configure PID parameters.

Definition at line 68 of file pid2.h.

void Pid::CopyHistory ( const Pid pid) [inline]

Copy the error history from another PID.

Parameters:
pidThe PID controller that has the history to copy

Definition at line 148 of file pid2.h.

float Pid::Update ( float  error,
float  output 
) [inline]

Update PID control output.

Parameters:
errorcurrent output error
outputcurrent output level
Returns:
recommended change in output

Definition at line 88 of file pid2.h.


Member Data Documentation

float Pid::C [protected]

tracker to adapt integral

Definition at line 170 of file pid2.h.

float Pid::dstate [protected]

previous output level

Definition at line 163 of file pid2.h.

float Pid::istate [protected]

integrator state

Definition at line 164 of file pid2.h.

float Pid::kd [protected]

derivative gain

Definition at line 167 of file pid2.h.

float Pid::ki [protected]

integral gain

Definition at line 166 of file pid2.h.

float Pid::kp [protected]

proportional gain

Definition at line 165 of file pid2.h.

std::string Pid::name [protected]

control output name

Definition at line 160 of file pid2.h.

float Pid::omax [protected]

output maximum limit

Definition at line 168 of file pid2.h.

float Pid::omin [protected]

output minimum limit

Definition at line 169 of file pid2.h.

bool Pid::starting [protected]

Definition at line 172 of file pid2.h.


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


art_common
Author(s): Austin Robot Technology
autogenerated on Fri Jan 3 2014 11:08:22