simulated_plant_threaded.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
26 
27 #include <corbo-core/global.h>
28 #include <corbo-core/time.h>
29 
30 #include <memory>
31 #include <thread>
32 
33 namespace corbo {
34 
36 
38  : SimulatedPlant(dynamics, output)
39 {
40 }
41 
43 {
44  _stop_thread = true;
45  if (_worker_thread.joinable())
46  {
47  _worker_thread.join();
48  }
49 }
50 
52 {
53  if (!_dynamics || !_output || !_integrator) return false;
54 
55  // initialize control vector with zeros
56  _control.setZero(_dynamics->getInputDimension());
57 
58  _stop_thread = false;
59 
61  return true;
62 }
63 
65 {
66  _stop_thread = true;
67  _worker_thread.join();
68 }
69 
71 {
72  _stop_thread = true;
74 
76 }
77 
79 {
81  StateVector next_state(x.rows());
82  ControlVector u;
83 
84  Duration dt(1.0 / _sim_rate);
85  Time t(0);
86 
87  std::vector<std::pair<double, ControlVector>> delayed_u_seq;
88 
90 
91  Rate sim_rate(_sim_rate);
92  while (!_stop_thread && ok())
93  {
94  {
95  std::lock_guard<std::mutex> locker(_control_mutex);
96  u = _control; // Get most recent control vector
97  }
98  {
99  std::lock_guard<std::mutex> locker(_current_state_mutex);
100  x = _current_state; // Get current state vector
101  }
102 
103  // disturb input if desired
104  ControlVector u_disturbed(u.rows());
105  if (_input_disturbance)
106  _input_disturbance->disturb(t, u, u_disturbed);
107  else
108  u_disturbed = u;
109 
110  // we might have deadtimes
111  delayed_u_seq.clear();
112 
113  _time_value_buffer.appendValues(t.toSec(), u_disturbed);
114  _time_value_buffer.getValues(t.toSec() - _dynamics->getDeadTime(), dt.toSec(), delayed_u_seq);
115 
116  for (int i = 0; i < delayed_u_seq.size(); ++i)
117  {
118  double cur_dt = delayed_u_seq[i].first;
119 
120  if (_dynamics->isContinuousTime())
121  {
122  // _integrator->integrate(_current_state, u, dt.toSec(), *_dynamics, next_state);
123  _integrator->solveIVP(x, delayed_u_seq[i].second, cur_dt, *_dynamics, next_state);
124  }
125  else
126  {
127  // TODO(roesmann): we need to check how discrete states behave with the deadtime simulator!!!
128  PRINT_WARNING_COND(_dynamics->getDeadTime() > 0, "Discrete-time systems with deadtime not yet tested/fully implemented...");
129  _dynamics->dynamics(x, delayed_u_seq[i].second, next_state);
130  }
131  x = next_state; // TODO(roesmann): we can avoid this if the integrator would not be affacted by alias
132  t += Duration(cur_dt);
133  }
134 
135  // write values back to shared cache
136  {
137  std::lock_guard<std::mutex> locker(_current_state_mutex);
138  _current_state = x; // Get current state vector
139  }
140 
141  // TODO(roesmann): should we use the lastCycleTime() to update our simulation dt?
142  // This might introduce new effects, so let's define at least the following warning:
143  if (!sim_rate.sleep())
144  {
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.");
147  }
148  }
149 }
150 
151 bool SimulatedPlantThreaded::control(const TimeSeries::ConstPtr& u_sequence, const TimeSeries::ConstPtr& x_sequence, const Duration& dt,
152  const Time& t, SignalTargetInterface* /*signal_target*/, const std::string& /*ns*/)
153 {
154  if (u_sequence->getTimeDimension() < 1)
155  {
156  PRINT_ERROR_NAMED("u_sequence is empty.");
157  return false;
158  }
159 
160  {
161  std::lock_guard<std::mutex> locker(_control_mutex);
162  _control = u_sequence->getValuesMap(0); // Get most recent control vector
163  }
164 
165  return true;
166 }
167 
168 bool SimulatedPlantThreaded::output(OutputVector& output, const Time& t, SignalTargetInterface* signal_target, const std::string& ns)
169 {
170  if (!_output) return false;
171 
172  {
173  std::lock_guard<std::mutex> locker(_current_state_mutex);
174  _output->output(_current_state, output);
175 
176  if (signal_target) signal_target->sendMeasurement(ns + "plant/state", t.toSec(), _current_state);
177  }
178 
179  // disturb output if desired
181 
182  return true;
183 }
184 
186 {
187  std::lock_guard<std::mutex> l(_current_state_mutex);
188  bool success = setInitialState(state);
189  return success;
190 }
191 
192 #ifdef MESSAGE_SUPPORT
193 void SimulatedPlantThreaded::toMessage(corbo::messages::SimulatedPlantThreaded& message) const
194 {
195  SimulatedPlant::toMessage(*message.mutable_simulated_plant());
196 
197  message.set_sim_rate(_sim_rate);
198 }
199 
200 void SimulatedPlantThreaded::fromMessage(const corbo::messages::SimulatedPlantThreaded& message, std::stringstream* issues)
201 {
202  SimulatedPlant::fromMessage(message.simulated_plant(), issues);
203 
204  _sim_rate = message.sim_rate();
205  if (_sim_rate <= 0)
206  {
207  if (issues) *issues << "SimulatedPlantThreaded:: sim_rate must be positive" << std::endl;
208  _sim_rate = 10;
209  }
210 }
211 #endif
212 
213 } // namespace corbo
corbo::SimulatedPlantThreaded::_stop_thread
bool _stop_thread
Definition: simulated_plant_threaded.h:155
PRINT_WARNING_NAMED
#define PRINT_WARNING_NAMED(msg)
Definition: console.h:255
corbo::SimulatedPlant::reset
void reset() override
Definition: simulated_plant.cpp:219
global.h
corbo::SimulatedPlant::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: simulated_plant.h:113
PRINT_ERROR_NAMED
#define PRINT_ERROR_NAMED(msg)
Definition: console.h:260
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::TimeValueBuffer::getValues
void getValues(double ts, double dt, std::vector< std::pair< double, Eigen::VectorXd >> &useq_out)
Compute the delayed values.
Definition: time_value_buffer.cpp:52
corbo::TimeValueBuffer::setInitialValue
void setInitialValue(const Eigen::Ref< const Eigen::VectorXd > &uinit)
Specify initial value.
Definition: time_value_buffer.h:123
corbo::SimulatedPlantThreaded::SimulatedPlantThreaded
SimulatedPlantThreaded()
Default constructor.
Definition: simulated_plant_threaded.cpp:57
corbo::SimulatedPlant::_output
SystemOutputInterface::Ptr _output
Definition: simulated_plant.h:170
corbo::TimeSeries::ConstPtr
std::shared_ptr< const TimeSeries > ConstPtr
Definition: time_series.h:109
corbo::TimeValueBuffer::appendValues
void appendValues(double t, const Eigen::Ref< const Eigen::VectorXd > &u)
Definition: time_value_buffer.cpp:111
corbo::SimulatedPlant::_current_state
StateVector _current_state
Definition: simulated_plant.h:181
corbo::SimulatedPlant::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: simulated_plant.h:172
corbo::SimulatedPlantThreaded::reset
void reset() override
Definition: simulated_plant_threaded.cpp:92
corbo::SimulatedPlantThreaded::initialize
bool initialize() override
Initialize plant.
Definition: simulated_plant_threaded.cpp:73
corbo::TimeValueBuffer::isEmpty
bool isEmpty() const
Definition: time_value_buffer.h:125
corbo::PlantInterface::ControlVector
Eigen::VectorXd ControlVector
Definition: plant_interface.h:102
corbo::SimulatedPlantThreaded::output
bool output(OutputVector &output, const Time &t, SignalTargetInterface *signal_target=nullptr, const std::string &ns="") override
Retrieve current plant output (measurements)
Definition: simulated_plant_threaded.cpp:190
corbo::SimulatedPlantThreaded::_current_state_mutex
std::mutex _current_state_mutex
Definition: simulated_plant_threaded.h:160
corbo::SimulatedPlantThreaded::setState
bool setState(const Eigen::Ref< const Eigen::VectorXd > &state) override
Set/move plant to a desired state (if possible)
Definition: simulated_plant_threaded.cpp:207
corbo::SimulatedPlantThreaded::~SimulatedPlantThreaded
virtual ~SimulatedPlantThreaded()
Definition: simulated_plant_threaded.cpp:64
corbo::Duration
Representation of time durations.
Definition: time.h:128
time.h
x
Scalar * x
Definition: level1_cplx_impl.h:89
PRINT_WARNING_COND
#define PRINT_WARNING_COND(cond, msg)
Print msg-stream only if cond == true.
Definition: console.h:159
corbo::SimulatedPlant::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: simulated_plant.h:169
corbo::SimulatedPlant::_output_disturbance
DisturbanceInterface::Ptr _output_disturbance
Definition: simulated_plant.h:175
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
corbo::SimulatedPlant::_input_disturbance
DisturbanceInterface::Ptr _input_disturbance
Definition: simulated_plant.h:174
corbo::SimulatedPlantThreaded::simulate
void simulate()
Definition: simulated_plant_threaded.cpp:100
corbo::SimulatedPlant::_time_value_buffer
TimeValueBuffer _time_value_buffer
Definition: simulated_plant.h:178
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::SimulatedPlantThreaded::_sim_rate
double _sim_rate
Definition: simulated_plant_threaded.h:152
corbo::SimulatedPlantThreaded::_worker_thread
std::thread _worker_thread
Definition: simulated_plant_threaded.h:154
corbo::SimulatedPlantThreaded::_control
ControlVector _control
Definition: simulated_plant_threaded.h:158
corbo::Time
Representation of time stamps.
Definition: time.h:273
corbo::SystemOutputInterface::Ptr
std::shared_ptr< SystemOutputInterface > Ptr
Definition: output_function_interface.h:109
corbo::SimulatedPlantThreaded::_control_mutex
std::mutex _control_mutex
Definition: simulated_plant_threaded.h:157
corbo::SimulatedPlantThreaded::control
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.
Definition: simulated_plant_threaded.cpp:173
corbo::ok
bool ok()
global method to check whether to proceed or cancel the current action
Definition: global.cpp:54
corbo::SimulatedPlant::setInitialState
bool setInitialState(const StateVector &x_init)
Specify an initial state x0 [SystemDynamicsInterface::getStateDimension() x 1].
Definition: simulated_plant.cpp:202
corbo::SimulatedPlantThreaded::StateVector
Eigen::VectorXd StateVector
Definition: simulated_plant_threaded.h:99
simulated_plant_threaded.h
corbo::SimulatedPlantThreaded::stop
void stop() override
Stop plant (you might probably use this to set the plant into a safe setpoint)
Definition: simulated_plant_threaded.cpp:86
corbo::Rate
Rate objects can be used to run loops at a desired rate.
Definition: time.h:375


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:14