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 (const ros::NodeHandle &node) |
| Configure PID parameters.
|
virtual void | Configure (float kp, float ki, float kd, float omax, float omin, float C) |
| Configure all PID parameters.
|
virtual void | Configure (float kp, float ki, float kd) |
| Configure PID gains.
|
void | CopyHistory (const Pid *pid) |
| Copy the error history from another PID.
|
| Pid (const char *ctlname, float kp, float ki, float kd, float omax=FLT_MAX, float omin=-FLT_MAX, float C=0.0) |
| Pid (const char *ctlname) |
| Constructor.
|
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:
-
| ctlname | control 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] |
virtual Pid::~Pid |
( |
|
) |
[inline, virtual] |
Member Function Documentation
void Pid::CfgParam |
( |
const ros::NodeHandle & |
node, |
|
|
const char * |
pname, |
|
|
float * |
fvalue | |
|
) |
| | [inline, protected] |
Configure one PID parameter.
- Parameters:
-
| node | node handle for parameter server |
| pname | base name for this parameter |
| fvalue | place 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 |
( |
const ros::NodeHandle & |
node |
) |
[inline, virtual] |
Configure PID parameters.
Definition at line 68 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 |
( |
float |
kp, |
|
|
float |
ki, |
|
|
float |
kd | |
|
) |
| | [inline, virtual] |
Configure PID gains.
Definition at line 48 of file pid2.h.
void Pid::CopyHistory |
( |
const Pid * |
pid |
) |
[inline] |
Copy the error history from another PID.
- Parameters:
-
| pid | The 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:
-
| error | current output error |
| output | current output level |
- Returns:
- recommended change in output
Definition at line 88 of file pid2.h.
Member Data Documentation
tracker to adapt integral
Definition at line 170 of file pid2.h.
previous output level
Definition at line 163 of file pid2.h.
integrator state
Definition at line 164 of file pid2.h.
derivative gain
Definition at line 167 of file pid2.h.
integral gain
Definition at line 166 of file pid2.h.
proportional gain
Definition at line 165 of file pid2.h.
control output name
Definition at line 160 of file pid2.h.
output maximum limit
Definition at line 168 of file pid2.h.
output minimum limit
Definition at line 169 of file pid2.h.
The documentation for this class was generated from the following file: