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

Adapter class for plant simulation. More...

#include <simulated_plant.h>

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

Public Types

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

Protected Attributes

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
 

Additional Inherited Members

- Static Public Member Functions inherited from corbo::PlantInterface
static Factory< PlantInterface > & getFactory ()
 Get access to the associated factory. More...
 

Detailed Description

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.

See also
SimulatedPlantThreaded 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 56 of file simulated_plant.h.

Member Typedef Documentation

◆ StateVector

using corbo::SimulatedPlant::StateVector = Eigen::VectorXd

Definition at line 59 of file simulated_plant.h.

Constructor & Destructor Documentation

◆ SimulatedPlant() [1/2]

corbo::SimulatedPlant::SimulatedPlant ( )

Default constructor.

Definition at line 33 of file simulated_plant.cpp.

◆ SimulatedPlant() [2/2]

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.

Member Function Documentation

◆ control()

bool corbo::SimulatedPlant::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.

Implements corbo::PlantInterface.

Reimplemented in corbo::SimulatedPlantThreaded.

Definition at line 91 of file simulated_plant.cpp.

◆ getAvailableSignals()

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

Parameters
[in,out]signal_targetTarget for occuring signals [optional]

Reimplemented from corbo::PlantInterface.

Definition at line 192 of file simulated_plant.cpp.

◆ getInputDimension()

int corbo::SimulatedPlant::getInputDimension ( ) const
inlineoverridevirtual

Return the plant input dimension (u)

Implements corbo::PlantInterface.

Definition at line 69 of file simulated_plant.h.

◆ getInstance()

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

◆ getOutputDimension()

int corbo::SimulatedPlant::getOutputDimension ( ) const
overridevirtual

Return the plant output dimension (y)

Implements corbo::PlantInterface.

Definition at line 48 of file simulated_plant.cpp.

◆ output()

bool corbo::SimulatedPlant::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.

Implements corbo::PlantInterface.

Reimplemented in corbo::SimulatedPlantThreaded.

Definition at line 150 of file simulated_plant.cpp.

◆ requiresFutureControls()

bool corbo::SimulatedPlant::requiresFutureControls ( ) const
inlineoverridevirtual

Implements corbo::PlantInterface.

Definition at line 73 of file simulated_plant.h.

◆ requiresFutureStates()

bool corbo::SimulatedPlant::requiresFutureStates ( ) const
inlineoverridevirtual

Implements corbo::PlantInterface.

Definition at line 75 of file simulated_plant.h.

◆ reset()

void corbo::SimulatedPlant::reset ( )
overridevirtual

Reimplemented from corbo::PlantInterface.

Reimplemented in corbo::SimulatedPlantThreaded.

Definition at line 197 of file simulated_plant.cpp.

◆ setInitialState()

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.

◆ setInputDisturbance()

void corbo::SimulatedPlant::setInputDisturbance ( DisturbanceInterface::Ptr  disturbance)

Set plant input disturbance model.

Definition at line 174 of file simulated_plant.cpp.

◆ setIntegrator()

void corbo::SimulatedPlant::setIntegrator ( NumericalIntegratorExplicitInterface::Ptr  integrator)

Set a numerical integrator for continuous-time dynamics.

Definition at line 172 of file simulated_plant.cpp.

◆ setOutputDisturbance()

void corbo::SimulatedPlant::setOutputDisturbance ( DisturbanceInterface::Ptr  disturbance)

Set plant output disturbance model.

Definition at line 176 of file simulated_plant.cpp.

◆ setOutputFunction()

void corbo::SimulatedPlant::setOutputFunction ( SystemOutputInterface::Ptr  output)

Set the output function of the simulated plant.

Definition at line 170 of file simulated_plant.cpp.

◆ setState()

bool corbo::SimulatedPlant::setState ( const Eigen::Ref< const Eigen::VectorXd > &  state)
inlineoverridevirtual

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

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

Reimplemented from corbo::PlantInterface.

Reimplemented in corbo::SimulatedPlantThreaded.

Definition at line 91 of file simulated_plant.h.

◆ setStateDisturbance()

void corbo::SimulatedPlant::setStateDisturbance ( DisturbanceInterface::Ptr  disturbance)

Set plant state disturbance model.

Definition at line 178 of file simulated_plant.cpp.

◆ setSystemDynamics()

void corbo::SimulatedPlant::setSystemDynamics ( SystemDynamicsInterface::Ptr  dynamics)

Set the system dynamics of the simulated plant.

Definition at line 162 of file simulated_plant.cpp.

Member Data Documentation

◆ _current_control

ControlVector corbo::SimulatedPlant::_current_control
protected

Definition at line 138 of file simulated_plant.h.

◆ _current_state

StateVector corbo::SimulatedPlant::_current_state
protected

Definition at line 137 of file simulated_plant.h.

◆ _dynamics

SystemDynamicsInterface::Ptr corbo::SimulatedPlant::_dynamics
protected

Definition at line 125 of file simulated_plant.h.

◆ _initial_state

StateVector corbo::SimulatedPlant::_initial_state
protected

Definition at line 136 of file simulated_plant.h.

◆ _input_disturbance

DisturbanceInterface::Ptr corbo::SimulatedPlant::_input_disturbance
protected

Definition at line 130 of file simulated_plant.h.

◆ _integrator

NumericalIntegratorExplicitInterface::Ptr corbo::SimulatedPlant::_integrator
protected

Definition at line 128 of file simulated_plant.h.

◆ _output

SystemOutputInterface::Ptr corbo::SimulatedPlant::_output
protected

Definition at line 126 of file simulated_plant.h.

◆ _output_disturbance

DisturbanceInterface::Ptr corbo::SimulatedPlant::_output_disturbance
protected

Definition at line 131 of file simulated_plant.h.

◆ _state_disturbance

DisturbanceInterface::Ptr corbo::SimulatedPlant::_state_disturbance
protected

Definition at line 132 of file simulated_plant.h.

◆ _time_value_buffer

TimeValueBuffer corbo::SimulatedPlant::_time_value_buffer
protected

Definition at line 134 of file simulated_plant.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