Step Response Generator. More...
#include <step_response_generator.h>
Public Member Functions | |
void | getAvailableSignals (SignalTargetInterface &signal_target, const std::string &ns="") const override |
Retrieve available signals from the controller. More... | |
const Eigen::VectorXd & | getControl () const |
int | getControlInputDimension () const override |
Return the control input dimension. More... | |
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... | |
bool | hasPiecewiseConstantControls () const override |
Return true if the controller returns piecewise constant control pieces. More... | |
bool | providesFutureControls () const override |
bool | providesFutureStates () const override |
void | reset () override |
Reset internal controller state and caches. More... | |
void | setControl (const Eigen::VectorXd &u_step) |
void | setStateDimension (int state_dim) |
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 |
StepResponseGenerator ()=default | |
![]() | |
virtual double | getControlDuration () const |
Return the duration for which the control u obtained from step() is valid (useful for asynchronous control) More... | |
virtual ControllerStatistics::Ptr | getStatistics () const |
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 Factory< ControllerInterface > & | getFactory () |
Get access to the associated factory. More... | |
Private Attributes | |
int | _state_dim = 0 |
Eigen::VectorXd | _u |
Additional Inherited Members | |
![]() | |
using | ControlVector = Eigen::VectorXd |
using | Ptr = std::shared_ptr< ControllerInterface > |
using | StateVector = Eigen::VectorXd |
using | UPtr = std::unique_ptr< ControllerInterface > |
Step Response Generator.
Generates a constant control input signal.
Definition at line 47 of file step_response_generator.h.
|
default |
|
inlineoverridevirtual |
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 from corbo::ControllerInterface.
Definition at line 85 of file step_response_generator.h.
|
inline |
Definition at line 69 of file step_response_generator.h.
|
inlineoverridevirtual |
Return the control input dimension.
Implements corbo::ControllerInterface.
Definition at line 53 of file step_response_generator.h.
|
inlineoverridevirtual |
Return a newly created shared instance of the implemented class.
Implements corbo::ControllerInterface.
Definition at line 64 of file step_response_generator.h.
|
inlinestatic |
Return a newly created shared instance of the implemented class (static method)
Definition at line 66 of file step_response_generator.h.
|
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.
Implements corbo::ControllerInterface.
Definition at line 55 of file step_response_generator.h.
|
inlineoverridevirtual |
Return true if the controller returns piecewise constant control pieces.
Implements corbo::ControllerInterface.
Definition at line 57 of file step_response_generator.h.
|
inlineoverridevirtual |
Implements corbo::ControllerInterface.
Definition at line 59 of file step_response_generator.h.
|
inlineoverridevirtual |
Implements corbo::ControllerInterface.
Definition at line 61 of file step_response_generator.h.
|
inlineoverridevirtual |
Reset internal controller state and caches.
Implements corbo::ControllerInterface.
Definition at line 113 of file step_response_generator.h.
|
inline |
Definition at line 68 of file step_response_generator.h.
|
inline |
Definition at line 70 of file step_response_generator.h.
|
inlineoverridevirtual |
Implements corbo::ControllerInterface.
Definition at line 73 of file step_response_generator.h.
|
private |
Definition at line 117 of file step_response_generator.h.
|
private |
Definition at line 116 of file step_response_generator.h.