Adapter class for plant simulation (threaded version) More...
#include <simulated_plant_threaded.h>
Public Types | |
using | StateVector = Eigen::VectorXd |
![]() | |
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... | |
Ptr | getInstance () const override |
Return a newly created shared instance of the implemented class. More... | |
bool | initialize () override |
Initialize plant. More... | |
bool | output (OutputVector &output, const Time &t, SignalTargetInterface *signal_target=nullptr, const std::string &ns="") override |
Retrieve current plant output (measurements) More... | |
void | reset () override |
void | setSimulationRate (double sim_rate) |
Specify rate for the simulation thread. More... | |
bool | setState (const Eigen::Ref< const Eigen::VectorXd > &state) override |
Set/move plant to a desired state (if possible) More... | |
SimulatedPlantThreaded () | |
Default constructor. More... | |
SimulatedPlantThreaded (SystemDynamicsInterface::Ptr dynamics, SystemOutputInterface::Ptr output) | |
Construct simulated plant with system dynamics and output function. More... | |
void | stop () override |
Stop plant (you might probably use this to set the plant into a safe setpoint) More... | |
virtual | ~SimulatedPlantThreaded () |
![]() | |
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... | |
int | getOutputDimension () const override |
Return the plant output dimension (y) More... | |
bool | requiresFutureControls () const override |
bool | requiresFutureStates () const 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... | |
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 | ~PlantInterface () |
Virtual destructor. More... | |
Protected Member Functions | |
void | simulate () |
Private Attributes | |
ControlVector | _control |
std::mutex | _control_mutex |
std::mutex | _current_state_mutex |
double | _sim_rate = 10 |
bool | _stop_thread = false |
std::thread | _worker_thread |
Additional Inherited Members | |
![]() | |
static Factory< PlantInterface > & | getFactory () |
Get access to the associated factory. More... | |
![]() | |
ControlVector | _current_control |
StateVector | _current_state |
SystemDynamicsInterface::Ptr | _dynamics |
StateVector | _initial_state |
DisturbanceInterface::Ptr | _input_disturbance |
NumericalIntegratorExplicitInterface::Ptr | _integrator |
SystemOutputInterface::Ptr | _output |
DisturbanceInterface::Ptr | _output_disturbance |
DisturbanceInterface::Ptr | _state_disturbance |
TimeValueBuffer | _time_value_buffer |
Adapter class for plant simulation (threaded version)
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 52 of file simulated_plant_threaded.h.
using corbo::SimulatedPlantThreaded::StateVector = Eigen::VectorXd |
Definition at line 55 of file simulated_plant_threaded.h.
corbo::SimulatedPlantThreaded::SimulatedPlantThreaded | ( | ) |
Default constructor.
Definition at line 35 of file simulated_plant_threaded.cpp.
corbo::SimulatedPlantThreaded::SimulatedPlantThreaded | ( | SystemDynamicsInterface::Ptr | dynamics, |
SystemOutputInterface::Ptr | output | ||
) |
Construct simulated plant with system dynamics and output function.
Definition at line 37 of file simulated_plant_threaded.cpp.
|
virtual |
Definition at line 42 of file simulated_plant_threaded.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] |
Reimplemented from corbo::SimulatedPlant.
Definition at line 151 of file simulated_plant_threaded.cpp.
|
inlineoverridevirtual |
Return a newly created shared instance of the implemented class.
Reimplemented from corbo::SimulatedPlant.
Definition at line 65 of file simulated_plant_threaded.h.
|
overridevirtual |
Initialize plant.
Reimplemented from corbo::PlantInterface.
Definition at line 51 of file simulated_plant_threaded.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] |
Reimplemented from corbo::SimulatedPlant.
Definition at line 168 of file simulated_plant_threaded.cpp.
|
overridevirtual |
Reimplemented from corbo::SimulatedPlant.
Definition at line 70 of file simulated_plant_threaded.cpp.
|
inline |
Specify rate for the simulation thread.
Definition at line 87 of file simulated_plant_threaded.h.
|
overridevirtual |
Set/move plant to a desired state (if possible)
[in] | Desired | state vector |
Reimplemented from corbo::SimulatedPlant.
Definition at line 185 of file simulated_plant_threaded.cpp.
|
protected |
Definition at line 78 of file simulated_plant_threaded.cpp.
|
overridevirtual |
Stop plant (you might probably use this to set the plant into a safe setpoint)
Reimplemented from corbo::PlantInterface.
Definition at line 64 of file simulated_plant_threaded.cpp.
|
private |
Definition at line 114 of file simulated_plant_threaded.h.
|
private |
Definition at line 113 of file simulated_plant_threaded.h.
|
private |
Definition at line 116 of file simulated_plant_threaded.h.
|
private |
Definition at line 108 of file simulated_plant_threaded.h.
|
private |
Definition at line 111 of file simulated_plant_threaded.h.
|
private |
Definition at line 110 of file simulated_plant_threaded.h.