Go to the documentation of this file.
38 : SimulatedPlant(dynamics, output)
87 std::vector<std::pair<double, ControlVector>> delayed_u_seq;
111 delayed_u_seq.clear();
116 for (
int i = 0; i < delayed_u_seq.size(); ++i)
118 double cur_dt = delayed_u_seq[i].first;
129 _dynamics->dynamics(
x, delayed_u_seq[i].second, next_state);
132 t += Duration(cur_dt);
143 if (!sim_rate.sleep())
145 PRINT_WARNING_NAMED(
"Rate exceeded (" << sim_rate.lastCycleTime().toSec() * 1000.0 <<
"ms/" << dt.toSec() * 1000.0
146 <<
"ms). Simulation results are probably useless. You might reduce sim_rate.");
152 const Time& t, SignalTargetInterface* ,
const std::string& )
154 if (u_sequence->getTimeDimension() < 1)
162 _control = u_sequence->getValuesMap(0);
176 if (signal_target) signal_target->sendMeasurement(ns +
"plant/state", t.toSec(),
_current_state);
192 #ifdef MESSAGE_SUPPORT
193 void SimulatedPlantThreaded::toMessage(corbo::messages::SimulatedPlantThreaded& message)
const
195 SimulatedPlant::toMessage(*message.mutable_simulated_plant());
200 void SimulatedPlantThreaded::fromMessage(
const corbo::messages::SimulatedPlantThreaded& message, std::stringstream* issues)
202 SimulatedPlant::fromMessage(message.simulated_plant(), issues);
207 if (issues) *issues <<
"SimulatedPlantThreaded:: sim_rate must be positive" << std::endl;
#define PRINT_WARNING_NAMED(msg)
int getInputDimension() const override
Return the plant input dimension (u)
#define PRINT_ERROR_NAMED(msg)
void getValues(double ts, double dt, std::vector< std::pair< double, Eigen::VectorXd >> &useq_out)
Compute the delayed values.
void setInitialValue(const Eigen::Ref< const Eigen::VectorXd > &uinit)
Specify initial value.
SimulatedPlantThreaded()
Default constructor.
SystemOutputInterface::Ptr _output
std::shared_ptr< const TimeSeries > ConstPtr
void appendValues(double t, const Eigen::Ref< const Eigen::VectorXd > &u)
StateVector _current_state
NumericalIntegratorExplicitInterface::Ptr _integrator
bool initialize() override
Initialize plant.
Eigen::VectorXd ControlVector
bool output(OutputVector &output, const Time &t, SignalTargetInterface *signal_target=nullptr, const std::string &ns="") override
Retrieve current plant output (measurements)
std::mutex _current_state_mutex
bool setState(const Eigen::Ref< const Eigen::VectorXd > &state) override
Set/move plant to a desired state (if possible)
virtual ~SimulatedPlantThreaded()
Representation of time durations.
#define PRINT_WARNING_COND(cond, msg)
Print msg-stream only if cond == true.
SystemDynamicsInterface::Ptr _dynamics
DisturbanceInterface::Ptr _output_disturbance
std::shared_ptr< SystemDynamicsInterface > Ptr
DisturbanceInterface::Ptr _input_disturbance
TimeValueBuffer _time_value_buffer
A matrix or vector expression mapping an existing expression.
std::thread _worker_thread
Representation of time stamps.
std::shared_ptr< SystemOutputInterface > Ptr
std::mutex _control_mutex
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.
bool ok()
global method to check whether to proceed or cancel the current action
bool setInitialState(const StateVector &x_init)
Specify an initial state x0 [SystemDynamicsInterface::getStateDimension() x 1].
Eigen::VectorXd StateVector
void stop() override
Stop plant (you might probably use this to set the plant into a safe setpoint)
Rate objects can be used to run loops at a desired rate.
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:14