25 #ifndef SRC_PLANTS_INCLUDE_CORBO_PLANTS_SIMULATED_PLANT_H_ 26 #define SRC_PLANTS_INCLUDE_CORBO_PLANTS_SIMULATED_PLANT_H_ 67 Ptr getInstance()
const override {
return std::make_shared<SimulatedPlant>(); }
88 void reset()
override;
112 #ifdef MESSAGE_SUPPORT 113 void toMessage(messages::SimulatedPlant& message)
const;
116 void fromMessage(
const messages::SimulatedPlant& message, std::stringstream* issues =
nullptr);
119 void toMessage(messages::Plant& message)
const override { toMessage(*message.mutable_simulated_plant()); }
121 void fromMessage(
const messages::Plant& message, std::stringstream* issues =
nullptr)
override { fromMessage(message.simulated_plant(), issues); }
145 #endif // SRC_PLANTS_INCLUDE_CORBO_PLANTS_SIMULATED_PLANT_H_ void setOutputDisturbance(DisturbanceInterface::Ptr disturbance)
Set plant output disturbance model.
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
bool setInitialState(const StateVector &x_init)
Specify an initial state x0 [SystemDynamicsInterface::getStateDimension() x 1].
DisturbanceInterface::Ptr _state_disturbance
bool setState(const Eigen::Ref< const Eigen::VectorXd > &state) override
Set/move plant to a desired state (if possible)
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Set a numerical integrator for continuous-time dynamics.
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.
void setSystemDynamics(SystemDynamicsInterface::Ptr dynamics)
Set the system dynamics of the simulated plant.
Time Delay Object for Piecewise-Constant Signals.
StateVector _current_state
SystemOutputInterface::Ptr _output
NumericalIntegratorExplicitInterface::Ptr _integrator
Interface class for signal targets.
Representation of time stamps.
Adapter class for plant simulation.
std::shared_ptr< SystemOutputInterface > Ptr
StateVector _initial_state
DisturbanceInterface::Ptr _output_disturbance
bool output(OutputVector &output, const Time &t, SignalTargetInterface *signal_target=nullptr, const std::string &ns="") override
Retrieve current plant output (measurements)
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the plant.
void setStateDisturbance(DisturbanceInterface::Ptr disturbance)
Set plant state disturbance model.
std::shared_ptr< DisturbanceInterface > Ptr
bool requiresFutureStates() const override
Eigen::VectorXd StateVector
TimeValueBuffer _time_value_buffer
bool requiresFutureControls() const override
Eigen::VectorXd ControlVector
#define FACTORY_REGISTER_PLANT(type)
std::shared_ptr< PlantInterface > Ptr
std::shared_ptr< NumericalIntegratorExplicitInterface > Ptr
A matrix or vector expression mapping an existing expression.
SystemDynamicsInterface::Ptr _dynamics
int getOutputDimension() const override
Return the plant output dimension (y)
void setInputDisturbance(DisturbanceInterface::Ptr disturbance)
Set plant input disturbance model.
DisturbanceInterface::Ptr _input_disturbance
Eigen::VectorXd OutputVector
SimulatedPlant()
Default constructor.
void setOutputFunction(SystemOutputInterface::Ptr output)
Set the output function of the simulated plant.
std::shared_ptr< const TimeSeries > ConstPtr
int getInputDimension() const override
Return the plant input dimension (u)
Representation of time durations.
ControlVector _current_control
std::shared_ptr< SystemDynamicsInterface > Ptr
Interface class for plants.