Public Member Functions | Static Public Member Functions | Private Attributes | List of all members
corbo::PidController Class Reference

PID controller. More...

#include <pid_controller.h>

Inheritance diagram for corbo::PidController:
Inheritance graph
[legend]

Public Member Functions

void getAvailableSignals (SignalTargetInterface &signal_target, const std::string &ns="") const override
 Retrieve available signals from the controller. More...
 
int getControlInputDimension () const override
 Return the control input dimension. More...
 
const double & getGainD () const
 Set differential gain. More...
 
const double & getGainI () const
 Set integral gain. More...
 
const double & getGainP () const
 
Ptr getInstance () const override
 Return a newly created shared instance of the implemented class. More...
 
int getStateDimension () const override
 Return the dimension of the required plant state/output. More...
 
ControllerStatistics::Ptr getStatistics () const override
 
bool hasPiecewiseConstantControls () const override
 Return true if the controller returns piecewise constant control pieces. More...
 
 PidController ()
 
bool providesFutureControls () const override
 
bool providesFutureStates () const override
 
void publishError (bool active)
 Specify whether the control error should be published via signal. More...
 
void reset () override
 Reset internal controller state and caches. More...
 
void setGainD (double d_gain)
 
void setGainI (double i_gain)
 
void setGainP (double p_gain)
 Set proportional gain. More...
 
void setNumParallelPid (int num_parallel_pid)
 
bool step (const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface *signal_target=nullptr, ReferenceTrajectoryInterface *sref=nullptr, ReferenceTrajectoryInterface *xinit=nullptr, ReferenceTrajectoryInterface *uinit=nullptr, const std::string &ns="") override
 
- Public Member Functions inherited from corbo::ControllerInterface
virtual double getControlDuration () const
 Return the duration for which the control u obtained from step() is valid (useful for asynchronous control) More...
 
virtual bool initialize (const StateVector &x, ReferenceTrajectoryInterface &expected_xref, ReferenceTrajectoryInterface &expected_uref, const Duration &expected_dt, const Time &t, ReferenceTrajectoryInterface *expected_sref=nullptr)
 Initialize the controller. More...
 
virtual void sendSignals (double t, SignalTargetInterface &signal_target, const std::string &ns="") const
 
virtual bool step (const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, ControlVector &u, SignalTargetInterface *signal_target=nullptr, const std::string &ns="")
 Perform actual controller step / control law computation. More...
 
virtual bool supportsAsynchronousControl () const
 Specify whether the controllers step function is independent of dt and getControlDuration() returns a valid value. More...
 
virtual ~ControllerInterface ()
 Virtual destructor. More...
 

Static Public Member Functions

static Ptr getInstanceStatic ()
 Return a newly created shared instance of the implemented class (static method) More...
 
- Static Public Member Functions inherited from corbo::ControllerInterface
static Factory< ControllerInterface > & getFactory ()
 Get access to the associated factory. More...
 

Private Attributes

std::vector< double > _d_error
 
double _d_gain = 0.0
 
std::vector< double > _i_error
 
double _i_gain = 0.0
 
int _num_parallel_pid = 1
 
std::vector< double > _p_error
 
double _p_gain = 0.2
 
bool _publish_error = true
 

Additional Inherited Members

- Public Types inherited from corbo::ControllerInterface
using ControlVector = Eigen::VectorXd
 
using Ptr = std::shared_ptr< ControllerInterface >
 
using StateVector = Eigen::VectorXd
 
using UPtr = std::unique_ptr< ControllerInterface >
 

Detailed Description

PID controller.

Implementation of a discrete-time PID controller.

See also
ControllerInterface LqrController PredictiveController
Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)
Todo:
Anti-windup implementation

Definition at line 46 of file pid_controller.h.

Constructor & Destructor Documentation

◆ PidController()

corbo::PidController::PidController ( )

Definition at line 32 of file pid_controller.cpp.

Member Function Documentation

◆ getAvailableSignals()

void corbo::PidController::getAvailableSignals ( SignalTargetInterface signal_target,
const std::string &  ns = "" 
) const
overridevirtual

Retrieve available signals from the controller.

Register a-priori known signals at the signal target. Registration is optional. Note, during step() execution further signals might occur without registration (in case the they are not known in advance or the implementation lacks a proper registration).

Parameters
[in,out]signal_targetTarget for occuring signals [optional]

Reimplemented from corbo::ControllerInterface.

Definition at line 88 of file pid_controller.cpp.

◆ getControlInputDimension()

int corbo::PidController::getControlInputDimension ( ) const
inlineoverridevirtual

Return the control input dimension.

Implements corbo::ControllerInterface.

Definition at line 52 of file pid_controller.h.

◆ getGainD()

const double& corbo::PidController::getGainD ( ) const
inline

Set differential gain.

Definition at line 74 of file pid_controller.h.

◆ getGainI()

const double& corbo::PidController::getGainI ( ) const
inline

Set integral gain.

Definition at line 71 of file pid_controller.h.

◆ getGainP()

const double& corbo::PidController::getGainP ( ) const
inline

Definition at line 67 of file pid_controller.h.

◆ getInstance()

Ptr corbo::PidController::getInstance ( ) const
inlineoverridevirtual

Return a newly created shared instance of the implemented class.

Implements corbo::ControllerInterface.

Definition at line 63 of file pid_controller.h.

◆ getInstanceStatic()

static Ptr corbo::PidController::getInstanceStatic ( )
inlinestatic

Return a newly created shared instance of the implemented class (static method)

Definition at line 65 of file pid_controller.h.

◆ getStateDimension()

int corbo::PidController::getStateDimension ( ) const
inlineoverridevirtual

Return the dimension of the required plant state/output.

Depending on the controller type, the state dimension can also be just the plant output or the complete measured or observed state vector.

Returns
the controllers state dimension

Implements corbo::ControllerInterface.

Definition at line 54 of file pid_controller.h.

◆ getStatistics()

ControllerStatistics::Ptr corbo::PidController::getStatistics ( ) const
inlineoverridevirtual

Reimplemented from corbo::ControllerInterface.

Definition at line 94 of file pid_controller.h.

◆ hasPiecewiseConstantControls()

bool corbo::PidController::hasPiecewiseConstantControls ( ) const
inlineoverridevirtual

Return true if the controller returns piecewise constant control pieces.

Returns
true if the controls are piecewise constant

Implements corbo::ControllerInterface.

Definition at line 56 of file pid_controller.h.

◆ providesFutureControls()

bool corbo::PidController::providesFutureControls ( ) const
inlineoverridevirtual

Implements corbo::ControllerInterface.

Definition at line 58 of file pid_controller.h.

◆ providesFutureStates()

bool corbo::PidController::providesFutureStates ( ) const
inlineoverridevirtual

Implements corbo::ControllerInterface.

Definition at line 60 of file pid_controller.h.

◆ publishError()

void corbo::PidController::publishError ( bool  active)
inline

Specify whether the control error should be published via signal.

Definition at line 107 of file pid_controller.h.

◆ reset()

void corbo::PidController::reset ( )
overridevirtual

Reset internal controller state and caches.

Implements corbo::ControllerInterface.

Definition at line 98 of file pid_controller.cpp.

◆ setGainD()

void corbo::PidController::setGainD ( double  d_gain)
inline

Definition at line 75 of file pid_controller.h.

◆ setGainI()

void corbo::PidController::setGainI ( double  i_gain)
inline

Definition at line 72 of file pid_controller.h.

◆ setGainP()

void corbo::PidController::setGainP ( double  p_gain)
inline

Set proportional gain.

Definition at line 69 of file pid_controller.h.

◆ setNumParallelPid()

void corbo::PidController::setNumParallelPid ( int  num_parallel_pid)
inline

Definition at line 77 of file pid_controller.h.

◆ step()

bool corbo::PidController::step ( const StateVector x,
ReferenceTrajectoryInterface xref,
ReferenceTrajectoryInterface uref,
const Duration dt,
const Time t,
TimeSeries::Ptr  u_sequence,
TimeSeries::Ptr  x_sequence,
SignalTargetInterface signal_target = nullptr,
ReferenceTrajectoryInterface sref = nullptr,
ReferenceTrajectoryInterface xinit = nullptr,
ReferenceTrajectoryInterface uinit = nullptr,
const std::string &  ns = "" 
)
overridevirtual

Implements corbo::ControllerInterface.

Definition at line 34 of file pid_controller.cpp.

Member Data Documentation

◆ _d_error

std::vector<double> corbo::PidController::_d_error
private

Definition at line 118 of file pid_controller.h.

◆ _d_gain

double corbo::PidController::_d_gain = 0.0
private

Definition at line 113 of file pid_controller.h.

◆ _i_error

std::vector<double> corbo::PidController::_i_error
private

Definition at line 117 of file pid_controller.h.

◆ _i_gain

double corbo::PidController::_i_gain = 0.0
private

Definition at line 112 of file pid_controller.h.

◆ _num_parallel_pid

int corbo::PidController::_num_parallel_pid = 1
private

Definition at line 121 of file pid_controller.h.

◆ _p_error

std::vector<double> corbo::PidController::_p_error
private

Definition at line 116 of file pid_controller.h.

◆ _p_gain

double corbo::PidController::_p_gain = 0.2
private

Definition at line 111 of file pid_controller.h.

◆ _publish_error

bool corbo::PidController::_publish_error = true
private

Definition at line 123 of file pid_controller.h.


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


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03