Interface class for controllers. More...
#include <controller_interface.h>
Public Types | |
using | ControlVector = Eigen::VectorXd |
using | Ptr = std::shared_ptr< ControllerInterface > |
using | StateVector = Eigen::VectorXd |
using | UPtr = std::unique_ptr< ControllerInterface > |
Public Member Functions | |
virtual void | getAvailableSignals (SignalTargetInterface &signal_target, const std::string &ns="") const |
Retrieve available signals from the controller. More... | |
virtual double | getControlDuration () const |
Return the duration for which the control u obtained from step() is valid (useful for asynchronous control) More... | |
virtual int | getControlInputDimension () const =0 |
Return the control input dimension. More... | |
virtual Ptr | getInstance () const =0 |
Return a newly created shared instance of the implemented class. More... | |
virtual int | getStateDimension () const =0 |
Return the dimension of the required plant state/output. More... | |
virtual ControllerStatistics::Ptr | getStatistics () const |
virtual bool | hasPiecewiseConstantControls () const =0 |
Return true if the controller returns piecewise constant control pieces. 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 bool | providesFutureControls () const =0 |
virtual bool | providesFutureStates () const =0 |
virtual void | reset ()=0 |
Reset internal controller state and caches. 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 | 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="")=0 |
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 Factory< ControllerInterface > & | getFactory () |
Get access to the associated factory. More... | |
Interface class for controllers.
This class specifies methods that are required to be implemented by specific controllers in order to allow their general utilization in a variety of control tasks.
Definition at line 58 of file controller_interface.h.
using corbo::ControllerInterface::ControlVector = Eigen::VectorXd |
Definition at line 64 of file controller_interface.h.
using corbo::ControllerInterface::Ptr = std::shared_ptr<ControllerInterface> |
Definition at line 61 of file controller_interface.h.
using corbo::ControllerInterface::StateVector = Eigen::VectorXd |
Definition at line 63 of file controller_interface.h.
using corbo::ControllerInterface::UPtr = std::unique_ptr<ControllerInterface> |
Definition at line 62 of file controller_interface.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 67 of file controller_interface.h.
|
inlinevirtual |
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).
[in,out] | signal_target | Target for occuring signals [optional] |
Reimplemented in corbo::DualModeController, corbo::PidController, corbo::PredictiveController, corbo::StepResponseGenerator, and corbo::SimpleStateController.
Definition at line 152 of file controller_interface.h.
|
inlinevirtual |
Return the duration for which the control u obtained from step() is valid (useful for asynchronous control)
Reimplemented in corbo::DualModeController, and corbo::PredictiveController.
Definition at line 136 of file controller_interface.h.
|
pure virtual |
Return the control input dimension.
Implemented in corbo::PredictiveController, corbo::DualModeController, corbo::StepResponseGenerator, corbo::PidController, and corbo::SimpleStateController.
|
inlinestatic |
Get access to the associated factory.
Definition at line 73 of file controller_interface.h.
|
pure virtual |
Return a newly created shared instance of the implemented class.
Implemented in corbo::DualModeController, corbo::PredictiveController, corbo::StepResponseGenerator, corbo::PidController, and corbo::SimpleStateController.
|
pure virtual |
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.
Implemented in corbo::PredictiveController, corbo::DualModeController, corbo::StepResponseGenerator, corbo::PidController, and corbo::SimpleStateController.
|
inlinevirtual |
Reimplemented in corbo::PredictiveController, corbo::DualModeController, and corbo::PidController.
Definition at line 156 of file controller_interface.h.
|
pure virtual |
Return true if the controller returns piecewise constant control pieces.
Implemented in corbo::PredictiveController, corbo::DualModeController, corbo::StepResponseGenerator, corbo::PidController, and corbo::SimpleStateController.
|
inlinevirtual |
Initialize the controller.
Initialization should be optional but it should facilitate memory allocation and trajectory initialization respectively warm starting.
[in] | x | Current plant state [getStateDimension() x 1] |
[in] | expected_xref | State reference (writable in order to allow to the reference object to precompute caches) |
[in] | expected_uref | Control reference (writable in order to allow to the reference object to precompute caches) |
[in] | expected_dt | Expected sampling interval length (controller rate) |
[in] | t | Current time stamp (can be sim-time or system-time, but compatible to state and control references) |
Reimplemented in corbo::DualModeController, corbo::PredictiveController, and corbo::SimpleStateController.
Definition at line 109 of file controller_interface.h.
|
pure virtual |
|
pure virtual |
|
pure virtual |
Reset internal controller state and caches.
Implemented in corbo::StepResponseGenerator, corbo::DualModeController, corbo::PidController, corbo::PredictiveController, and corbo::SimpleStateController.
|
inlinevirtual |
Reimplemented in corbo::PredictiveController, and corbo::DualModeController.
Definition at line 154 of file controller_interface.h.
|
virtual |
Perform actual controller step / control law computation.
[in] | x | Current plant state [getStateDimension() x 1] |
[in] | xref | State reference (writable in order to allow to the reference object to precompute caches) |
[in] | uref | Control reference (writable in order to allow to the reference object to precompute caches) |
[in] | dt | Last sampling interval length (does not (!) mean that the subsequent one will be identical) |
[in] | t | Current time stamp (can be sim-time or system-time, but compatible to state and control references) |
[out] | u | Computed control input for the plant [getControlInputDimension() x 1] |
[in,out] | signal_target | Target for occuring signals [optional] |
u
was successful, false otherwise. Definition at line 29 of file controller_interface.cpp.
|
pure virtual |
|
inlinevirtual |
Specify whether the controllers step function is independent of dt and getControlDuration() returns a valid value.
Reimplemented in corbo::DualModeController, and corbo::PredictiveController.
Definition at line 138 of file controller_interface.h.