Adapter class for plant simulation. More...
#include <simulated_plant.h>
Public Types | |
using | StateVector = Eigen::VectorXd |
![]() | |
using | ControlVector = Eigen::VectorXd |
using | OutputVector = Eigen::VectorXd |
using | Ptr = std::shared_ptr< PlantInterface > |
using | StateVector = Eigen::VectorXd |
Public Member Functions | |
bool | control (const TimeSeries::ConstPtr &u_sequence, const TimeSeries::ConstPtr &x_sequence, const Duration &dt, const Time &t, SignalTargetInterface *signal_target=nullptr, const std::string &ns="") override |
Send commands to plant. More... | |
void | getAvailableSignals (SignalTargetInterface &signal_target, const std::string &ns="") const override |
Retrieve available signals from the plant. More... | |
int | getInputDimension () const override |
Return the plant input dimension (u) More... | |
Ptr | getInstance () const override |
Return a newly created shared instance of the implemented class. More... | |
int | getOutputDimension () const override |
Return the plant output dimension (y) More... | |
bool | output (OutputVector &output, const Time &t, SignalTargetInterface *signal_target=nullptr, const std::string &ns="") override |
Retrieve current plant output (measurements) More... | |
bool | requiresFutureControls () const override |
bool | requiresFutureStates () const override |
void | reset () override |
bool | setInitialState (const StateVector &x_init) |
Specify an initial state x0 [SystemDynamicsInterface::getStateDimension() x 1]. More... | |
void | setInputDisturbance (DisturbanceInterface::Ptr disturbance) |
Set plant input disturbance model. More... | |
void | setIntegrator (NumericalIntegratorExplicitInterface::Ptr integrator) |
Set a numerical integrator for continuous-time dynamics. More... | |
void | setOutputDisturbance (DisturbanceInterface::Ptr disturbance) |
Set plant output disturbance model. More... | |
void | setOutputFunction (SystemOutputInterface::Ptr output) |
Set the output function of the simulated plant. More... | |
bool | setState (const Eigen::Ref< const Eigen::VectorXd > &state) override |
Set/move plant to a desired state (if possible) More... | |
void | setStateDisturbance (DisturbanceInterface::Ptr disturbance) |
Set plant state disturbance model. More... | |
void | setSystemDynamics (SystemDynamicsInterface::Ptr dynamics) |
Set the system dynamics of the simulated plant. More... | |
SimulatedPlant () | |
Default constructor. More... | |
SimulatedPlant (SystemDynamicsInterface::Ptr dynamics, SystemOutputInterface::Ptr output) | |
Construct simulated plant with system dynamics and output function. More... | |
![]() | |
virtual bool | control (const ControlVector &u, const Duration &dt, const Time &t, SignalTargetInterface *signal_target=nullptr, const std::string &ns="") |
Send commands to plant. More... | |
virtual bool | initialize () |
Initialize plant. More... | |
virtual void | stop () |
Stop plant (you might probably use this to set the plant into a safe setpoint) More... | |
virtual | ~PlantInterface () |
Virtual destructor. More... | |
Additional Inherited Members | |
![]() | |
static Factory< PlantInterface > & | getFactory () |
Get access to the associated factory. More... | |
Adapter class for plant simulation.
This class provides a PlantInterface implementation for the simulation of plants defined in terms of a state space model, in particular a SystemDynamicsInterface and a SystemOutputInterface.
In the continuous-time case, a numerical integrator solves the initial value problem w.r.t. given control inputs.
Definition at line 56 of file simulated_plant.h.
using corbo::SimulatedPlant::StateVector = Eigen::VectorXd |
Definition at line 59 of file simulated_plant.h.
corbo::SimulatedPlant::SimulatedPlant | ( | ) |
Default constructor.
Definition at line 33 of file simulated_plant.cpp.
corbo::SimulatedPlant::SimulatedPlant | ( | SystemDynamicsInterface::Ptr | dynamics, |
SystemOutputInterface::Ptr | output | ||
) |
Construct simulated plant with system dynamics and output function.
Definition at line 39 of file simulated_plant.cpp.
|
overridevirtual |
Send commands to plant.
[in] | u_sequence | Sequence of controls that are commanded to the plant |
[in] | x_sequence | Sequence of states that are commanded to the plant |
[in] | dt | Specify the intended duration for the signal (usually only relevant for simulation) |
[in] | t | Current time stamp (can be sim-time or system-time, but compatible to state and control references) |
[in,out] | signal_target | Target for occuring signals [optional] |
Implements corbo::PlantInterface.
Reimplemented in corbo::SimulatedPlantThreaded.
Definition at line 91 of file simulated_plant.cpp.
|
overridevirtual |
Retrieve available signals from the plant.
Register a-priori known signals at the signal target. Registration is optional. Note, during control() or output() 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::PlantInterface.
Definition at line 192 of file simulated_plant.cpp.
|
inlineoverridevirtual |
Return the plant input dimension (u)
Implements corbo::PlantInterface.
Definition at line 69 of file simulated_plant.h.
|
inlineoverridevirtual |
Return a newly created shared instance of the implemented class.
Implements corbo::PlantInterface.
Reimplemented in corbo::SimulatedPlantThreaded.
Definition at line 67 of file simulated_plant.h.
|
overridevirtual |
Return the plant output dimension (y)
Implements corbo::PlantInterface.
Definition at line 48 of file simulated_plant.cpp.
|
overridevirtual |
Retrieve current plant output (measurements)
[out] | output | Plant output will be written to this vector [getOutputDimension() x 1] |
[in] | t | Current time stamp (can be sim-time or system-time, but compatible to state and control references) |
[in,out] | signal_target | Target for occuring signals [optional] |
Implements corbo::PlantInterface.
Reimplemented in corbo::SimulatedPlantThreaded.
Definition at line 150 of file simulated_plant.cpp.
|
inlineoverridevirtual |
Implements corbo::PlantInterface.
Definition at line 73 of file simulated_plant.h.
|
inlineoverridevirtual |
Implements corbo::PlantInterface.
Definition at line 75 of file simulated_plant.h.
|
overridevirtual |
Reimplemented from corbo::PlantInterface.
Reimplemented in corbo::SimulatedPlantThreaded.
Definition at line 197 of file simulated_plant.cpp.
bool corbo::SimulatedPlant::setInitialState | ( | const StateVector & | x_init | ) |
Specify an initial state x0 [SystemDynamicsInterface::getStateDimension() x 1].
Definition at line 180 of file simulated_plant.cpp.
void corbo::SimulatedPlant::setInputDisturbance | ( | DisturbanceInterface::Ptr | disturbance | ) |
Set plant input disturbance model.
Definition at line 174 of file simulated_plant.cpp.
void corbo::SimulatedPlant::setIntegrator | ( | NumericalIntegratorExplicitInterface::Ptr | integrator | ) |
Set a numerical integrator for continuous-time dynamics.
Definition at line 172 of file simulated_plant.cpp.
void corbo::SimulatedPlant::setOutputDisturbance | ( | DisturbanceInterface::Ptr | disturbance | ) |
Set plant output disturbance model.
Definition at line 176 of file simulated_plant.cpp.
void corbo::SimulatedPlant::setOutputFunction | ( | SystemOutputInterface::Ptr | output | ) |
Set the output function of the simulated plant.
Definition at line 170 of file simulated_plant.cpp.
|
inlineoverridevirtual |
Set/move plant to a desired state (if possible)
[in] | Desired | state vector |
Reimplemented from corbo::PlantInterface.
Reimplemented in corbo::SimulatedPlantThreaded.
Definition at line 91 of file simulated_plant.h.
void corbo::SimulatedPlant::setStateDisturbance | ( | DisturbanceInterface::Ptr | disturbance | ) |
Set plant state disturbance model.
Definition at line 178 of file simulated_plant.cpp.
void corbo::SimulatedPlant::setSystemDynamics | ( | SystemDynamicsInterface::Ptr | dynamics | ) |
Set the system dynamics of the simulated plant.
Definition at line 162 of file simulated_plant.cpp.
|
protected |
Definition at line 138 of file simulated_plant.h.
|
protected |
Definition at line 137 of file simulated_plant.h.
|
protected |
Definition at line 125 of file simulated_plant.h.
|
protected |
Definition at line 136 of file simulated_plant.h.
|
protected |
Definition at line 130 of file simulated_plant.h.
|
protected |
Definition at line 128 of file simulated_plant.h.
|
protected |
Definition at line 126 of file simulated_plant.h.
|
protected |
Definition at line 131 of file simulated_plant.h.
|
protected |
Definition at line 132 of file simulated_plant.h.
|
protected |
Definition at line 134 of file simulated_plant.h.