|
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 |
|
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...
|
|
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.
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_target | Target for occuring signals [optional] |
Reimplemented from corbo::ControllerInterface.
Definition at line 88 of file pid_controller.cpp.