Public Types | Public Member Functions | Static Public Member Functions | List of all members
corbo::ControllerInterface Class Referenceabstract

Interface class for controllers. More...

#include <controller_interface.h>

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

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...
 

Detailed Description

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.

Remarks
This interface is provided with factory support (ControllerFactory).
See also
PidController 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)

Definition at line 58 of file controller_interface.h.

Member Typedef Documentation

◆ ControlVector

Definition at line 64 of file controller_interface.h.

◆ Ptr

Definition at line 61 of file controller_interface.h.

◆ StateVector

using corbo::ControllerInterface::StateVector = Eigen::VectorXd

Definition at line 63 of file controller_interface.h.

◆ UPtr

Definition at line 62 of file controller_interface.h.

Constructor & Destructor Documentation

◆ ~ControllerInterface()

virtual corbo::ControllerInterface::~ControllerInterface ( )
inlinevirtual

Virtual destructor.

Definition at line 67 of file controller_interface.h.

Member Function Documentation

◆ getAvailableSignals()

virtual void corbo::ControllerInterface::getAvailableSignals ( SignalTargetInterface signal_target,
const std::string &  ns = "" 
) const
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).

Parameters
[in,out]signal_targetTarget 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.

◆ getControlDuration()

virtual double corbo::ControllerInterface::getControlDuration ( ) const
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.

◆ getControlInputDimension()

virtual int corbo::ControllerInterface::getControlInputDimension ( ) const
pure virtual

◆ getFactory()

static Factory<ControllerInterface>& corbo::ControllerInterface::getFactory ( )
inlinestatic

Get access to the associated factory.

Definition at line 73 of file controller_interface.h.

◆ getInstance()

virtual Ptr corbo::ControllerInterface::getInstance ( ) const
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.

◆ getStateDimension()

virtual int corbo::ControllerInterface::getStateDimension ( ) const
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.

Returns
the controllers state dimension

Implemented in corbo::PredictiveController, corbo::DualModeController, corbo::StepResponseGenerator, corbo::PidController, and corbo::SimpleStateController.

◆ getStatistics()

virtual ControllerStatistics::Ptr corbo::ControllerInterface::getStatistics ( ) const
inlinevirtual

◆ hasPiecewiseConstantControls()

virtual bool corbo::ControllerInterface::hasPiecewiseConstantControls ( ) const
pure virtual

Return true if the controller returns piecewise constant control pieces.

Returns
true if the controls are piecewise constant

Implemented in corbo::PredictiveController, corbo::DualModeController, corbo::StepResponseGenerator, corbo::PidController, and corbo::SimpleStateController.

◆ initialize()

virtual bool corbo::ControllerInterface::initialize ( const StateVector x,
ReferenceTrajectoryInterface expected_xref,
ReferenceTrajectoryInterface expected_uref,
const Duration expected_dt,
const Time t,
ReferenceTrajectoryInterface expected_sref = nullptr 
)
inlinevirtual

Initialize the controller.

Initialization should be optional but it should facilitate memory allocation and trajectory initialization respectively warm starting.

Parameters
[in]xCurrent plant state [getStateDimension() x 1]
[in]expected_xrefState reference (writable in order to allow to the reference object to precompute caches)
[in]expected_urefControl reference (writable in order to allow to the reference object to precompute caches)
[in]expected_dtExpected sampling interval length (controller rate)
[in]tCurrent time stamp (can be sim-time or system-time, but compatible to state and control references)
Returns
true if initialization was successful, false otherwise.

Reimplemented in corbo::DualModeController, corbo::PredictiveController, and corbo::SimpleStateController.

Definition at line 109 of file controller_interface.h.

◆ providesFutureControls()

virtual bool corbo::ControllerInterface::providesFutureControls ( ) const
pure virtual

◆ providesFutureStates()

virtual bool corbo::ControllerInterface::providesFutureStates ( ) const
pure virtual

◆ reset()

virtual void corbo::ControllerInterface::reset ( )
pure virtual

◆ sendSignals()

virtual void corbo::ControllerInterface::sendSignals ( double  t,
SignalTargetInterface signal_target,
const std::string &  ns = "" 
) const
inlinevirtual

Reimplemented in corbo::PredictiveController, and corbo::DualModeController.

Definition at line 154 of file controller_interface.h.

◆ step() [1/2]

bool corbo::ControllerInterface::step ( const StateVector x,
ReferenceTrajectoryInterface xref,
ReferenceTrajectoryInterface uref,
const Duration dt,
const Time t,
ControllerInterface::ControlVector u,
SignalTargetInterface signal_target = nullptr,
const std::string &  ns = "" 
)
virtual

Perform actual controller step / control law computation.

Parameters
[in]xCurrent plant state [getStateDimension() x 1]
[in]xrefState reference (writable in order to allow to the reference object to precompute caches)
[in]urefControl reference (writable in order to allow to the reference object to precompute caches)
[in]dtLast sampling interval length (does not (!) mean that the subsequent one will be identical)
[in]tCurrent time stamp (can be sim-time or system-time, but compatible to state and control references)
[out]uComputed control input for the plant [getControlInputDimension() x 1]
[in,out]signal_targetTarget for occuring signals [optional]
Returns
true if step was successful and computation of u was successful, false otherwise.

Definition at line 29 of file controller_interface.cpp.

◆ step() [2/2]

virtual bool corbo::ControllerInterface::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 = "" 
)
pure virtual

◆ supportsAsynchronousControl()

virtual bool corbo::ControllerInterface::supportsAsynchronousControl ( ) const
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.


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:02