Public Types | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
corbo::SimulatedPlantThreaded Class Reference

Adapter class for plant simulation (threaded version) More...

#include <simulated_plant_threaded.h>

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

Public Types

using StateVector = Eigen::VectorXd
 
- Public Types inherited from corbo::SimulatedPlant
using StateVector = Eigen::VectorXd
 
- Public Types inherited from corbo::PlantInterface
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 ()
 
- Public Member Functions inherited from corbo::SimulatedPlant
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...
 
- Public Member Functions inherited from corbo::PlantInterface
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 Public Member Functions inherited from corbo::PlantInterface
static Factory< PlantInterface > & getFactory ()
 Get access to the associated factory. More...
 
- Protected Attributes inherited from corbo::SimulatedPlant
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
 

Detailed Description

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.

See also
SimulatedPlant PlantInterface
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 52 of file simulated_plant_threaded.h.

Member Typedef Documentation

◆ StateVector

Definition at line 55 of file simulated_plant_threaded.h.

Constructor & Destructor Documentation

◆ SimulatedPlantThreaded() [1/2]

corbo::SimulatedPlantThreaded::SimulatedPlantThreaded ( )

Default constructor.

Definition at line 35 of file simulated_plant_threaded.cpp.

◆ SimulatedPlantThreaded() [2/2]

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.

◆ ~SimulatedPlantThreaded()

corbo::SimulatedPlantThreaded::~SimulatedPlantThreaded ( )
virtual

Definition at line 42 of file simulated_plant_threaded.cpp.

Member Function Documentation

◆ control()

bool corbo::SimulatedPlantThreaded::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 = "" 
)
overridevirtual

Send commands to plant.

Parameters
[in]u_sequenceSequence of controls that are commanded to the plant
[in]x_sequenceSequence of states that are commanded to the plant
[in]dtSpecify the intended duration for the signal (usually only relevant for simulation)
[in]tCurrent time stamp (can be sim-time or system-time, but compatible to state and control references)
[in,out]signal_targetTarget for occuring signals [optional]
Returns
true if transmission of commands was successful, otherwise false.

Reimplemented from corbo::SimulatedPlant.

Definition at line 151 of file simulated_plant_threaded.cpp.

◆ getInstance()

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

◆ initialize()

bool corbo::SimulatedPlantThreaded::initialize ( )
overridevirtual

Initialize plant.

Reimplemented from corbo::PlantInterface.

Definition at line 51 of file simulated_plant_threaded.cpp.

◆ output()

bool corbo::SimulatedPlantThreaded::output ( OutputVector output,
const Time t,
SignalTargetInterface signal_target = nullptr,
const std::string &  ns = "" 
)
overridevirtual

Retrieve current plant output (measurements)

Parameters
[out]outputPlant output will be written to this vector [getOutputDimension() x 1]
[in]tCurrent time stamp (can be sim-time or system-time, but compatible to state and control references)
[in,out]signal_targetTarget for occuring signals [optional]
Returns
true if receiving of measurements was successful, otherwise false.

Reimplemented from corbo::SimulatedPlant.

Definition at line 168 of file simulated_plant_threaded.cpp.

◆ reset()

void corbo::SimulatedPlantThreaded::reset ( )
overridevirtual

Reimplemented from corbo::SimulatedPlant.

Definition at line 70 of file simulated_plant_threaded.cpp.

◆ setSimulationRate()

void corbo::SimulatedPlantThreaded::setSimulationRate ( double  sim_rate)
inline

Specify rate for the simulation thread.

Definition at line 87 of file simulated_plant_threaded.h.

◆ setState()

bool corbo::SimulatedPlantThreaded::setState ( const Eigen::Ref< const Eigen::VectorXd > &  state)
overridevirtual

Set/move plant to a desired state (if possible)

Parameters
[in]Desiredstate vector
Returns
true if successful, false otherwise

Reimplemented from corbo::SimulatedPlant.

Definition at line 185 of file simulated_plant_threaded.cpp.

◆ simulate()

void corbo::SimulatedPlantThreaded::simulate ( )
protected

Definition at line 78 of file simulated_plant_threaded.cpp.

◆ stop()

void corbo::SimulatedPlantThreaded::stop ( )
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.

Member Data Documentation

◆ _control

ControlVector corbo::SimulatedPlantThreaded::_control
private

Definition at line 114 of file simulated_plant_threaded.h.

◆ _control_mutex

std::mutex corbo::SimulatedPlantThreaded::_control_mutex
private

Definition at line 113 of file simulated_plant_threaded.h.

◆ _current_state_mutex

std::mutex corbo::SimulatedPlantThreaded::_current_state_mutex
private

Definition at line 116 of file simulated_plant_threaded.h.

◆ _sim_rate

double corbo::SimulatedPlantThreaded::_sim_rate = 10
private

Definition at line 108 of file simulated_plant_threaded.h.

◆ _stop_thread

bool corbo::SimulatedPlantThreaded::_stop_thread = false
private

Definition at line 111 of file simulated_plant_threaded.h.

◆ _worker_thread

std::thread corbo::SimulatedPlantThreaded::_worker_thread
private

Definition at line 110 of file simulated_plant_threaded.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:03