task_open_loop_control.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 #include <corbo-core/console.h>
27 #include <corbo-core/time.h>
28 #include <corbo-core/time_series.h>
30 #include <string>
31 
32 namespace corbo {
33 
35 {
36  // default reference
37  _xreference = std::make_shared<StaticReference>(Eigen::Matrix<double, 1, 1>::Ones());
38  _ureference = std::make_shared<ZeroReference>(1);
39 }
40 
41 void OpenLoopControlTask::getAvailableSignals(const Environment& environment, SignalTargetInterface& signal_target, const std::string& ns) const
42 {
43  if (environment.getController())
44  {
45  environment.getController()->getAvailableSignals(signal_target);
46 
47  if (environment.getController()->getControlInputDimension() != property::INHERITED)
48  signal_target.registerMeasurement(ns + "control_input", environment.getController()->getControlInputDimension(), {}, true);
49  }
50 
51  if (environment.getPlant())
52  {
53  environment.getPlant()->getAvailableSignals(signal_target);
54  if (environment.getPlant()->getOutputDimension() != property::INHERITED)
55  signal_target.registerMeasurement(ns + "plant_output", environment.getPlant()->getOutputDimension());
56  }
57 
58  if (environment.getObserver())
59  {
60  environment.getObserver()->getAvailableSignals(signal_target);
61  if (environment.getObserver()->getStateDimension() != property::INHERITED)
62  signal_target.registerMeasurement(ns + "observed_states", environment.getObserver()->getStateDimension());
63  }
64 }
65 
66 void OpenLoopControlTask::performTask(Environment& environment, SignalTargetInterface* signal_target, std::string* msg, const std::string& ns)
67 {
68  // environment->reset();
69 
70  // initialize variables
71  Time t(0);
72  Duration dt(_dt);
73 
74  ControllerInterface* controller = environment.getController().get();
75  PlantInterface* plant = environment.getPlant().get();
76  ObserverInterface* observer = environment.getObserver().get();
77 
78  using ControlVector = Eigen::VectorXd;
79  using StateVector = Eigen::VectorXd;
80  using OutputVector = Eigen::VectorXd;
81 
82  TimeSeries::Ptr u_sequence = std::make_shared<TimeSeries>();
83  TimeSeries::Ptr x_sequence = std::make_shared<TimeSeries>();
84 
85  ControlVector u(controller->getControlInputDimension());
86  OutputVector y(plant->getOutputDimension());
87  StateVector x(controller->getStateDimension());
88 
89  if (!verify(environment, msg)) return;
90 
91  // initialize modules
92  if (!controller->initialize(x, *_xreference, *_ureference, dt, t)) PRINT_FATAL("Controller initialization failed.");
93  if (!plant->initialize()) PRINT_FATAL("Plant initialization failed.");
94 
95  // request open-loop control action
96  if (!plant->output(y, t, signal_target, ns)) PRINT_ERROR("OpenLoopControlTask::performTask(): error while retreiving plant output.");
97  if (!observer->observe(y, x, Duration(0), t, signal_target, ns)) PRINT_ERROR("OpenLoopControlTask::performTask(): observer error.");
98  Time time_pre_step = Time::now();
99 
100  // if (!controller->step(x, *_xreference, *_ureference, Duration(0), t, u, signal_target))
101  bool controller_success =
102  controller->step(x, *_xreference, *_ureference, Duration(0), t, u_sequence, x_sequence, signal_target, nullptr, nullptr, nullptr, ns);
103  if (!controller_success)
104  {
105  u.setZero();
106  PRINT_ERROR("OpenLoopControlTask::performTask(): controller error.");
107  }
108 
109  PRINT_INFO("Controller CPU time: " << (Time::now() - time_pre_step).toSec() * 1000 << " ms.");
110 
111  TimeSeries::Interpolation u_interp_strategy =
112  controller->hasPiecewiseConstantControls() ? TimeSeries::Interpolation::ZeroOrderHold : TimeSeries::Interpolation::Linear;
113 
114  // send controller signals
115  if (signal_target) controller->sendSignals(t.toSec(), *signal_target, ns);
116 
117  if (!u_sequence || u_sequence->getTimeDimension() < 1)
118  {
119  PRINT_ERROR("OpenLoopControlTask::performTask(): control does not provide any open-loop control sequence. Canceling.");
120  return;
121  }
122 
123  // set final time
124  Time tf(u_sequence->getTime().back() + 1e-12);
125 
126  Rate rate(_realtime_sync ? dt : Duration(1e-5)); // wait a small amount also if realtime sync is disabled
127 
128  int t_idx = 0; // just for the case (_dt <= 0)
129 
130  // perform actual open-loop task
131  while (t <= tf && ok())
132  {
133  // plant output
134  if (!plant->output(y, t, signal_target, ns)) PRINT_ERROR("OpenLoopControlTask::performTask(): error while retreiving plant output.");
135  if (signal_target) signal_target->sendMeasurement(ns + "plant_output", t.toSec(), y);
136 
137  // observer
138  if (!observer->observe(y, x, Duration(0), t, signal_target)) PRINT_ERROR("OpenLoopControlTask::performTask(): observer error.");
139  if (signal_target) signal_target->sendMeasurement(ns + "observed_states", t.toSec(), x);
140 
141  // get current u
142  if (controller_success && !u_sequence->getValuesInterpolate(t.toSec(), u, u_interp_strategy, TimeSeries::Extrapolation::ZeroOrderHold))
143  PRINT_ERROR("OpenLoopControlTask::performTask(): control sequence interpolation error.");
144 
145  if (signal_target) signal_target->sendMeasurement(ns + "control_input", t.toSec(), u);
146 
147  // if dt<=0 -> inherit from open loop sequence
148  if (_dt <= 0 && t_idx < u_sequence->getTimeDimension() - 1)
149  {
150  dt.fromSec(u_sequence->getTimeRef()[t_idx + 1] - u_sequence->getTimeRef()[t_idx]);
151  ++t_idx;
152  }
153 
154  // control plant
155  plant->control(u, dt, t, signal_target, ns);
156  // plant->control(u_sequence, x_sequence, dt, t, signal_target);
157  // this does not work in open-loop, since u_seq is not pruned w.r.t. current
158  // TODO(roesmann): add prune method to TimeSeries object
159 
160  if (!rate.sleep() && _realtime_sync)
161  {
162  PRINT_WARNING("OpenLoopControlTask(): rate exceeded (" << rate.lastCycleTime().toSec() << "s/" << dt << "s).");
163  }
164  t += dt;
165  }
166 
167  plant->stop();
168 
169  signal_target->sendMeasurement(ns + "ctrl_succeess", 0.0, {(double)controller_success});
170 }
171 
172 bool OpenLoopControlTask::verify(const Environment& environment, std::string* msg) const
173 {
174  bool ret_val = true;
175 
176  if (msg) msg->clear();
177 
178  if (environment.getController() && !environment.getController()->providesFutureControls())
179  {
180  ret_val = false;
181  if (msg) *msg += "The provided controller does not support open loop control tasks.\n";
182  return ret_val;
183  }
184 
185  // check if all objects are set
186  if (!_xreference)
187  {
188  ret_val = false;
189  if (msg) *msg += "State reference trajectory not specified for OpenLoopControlTask\n";
190  }
191 
192  // check if all objects are set
193  if (!_ureference)
194  {
195  ret_val = false;
196  if (msg) *msg += "Control reference trajectory not specified for OpenLoopControlTask\n";
197  }
198 
199  // verify environment
200  std::string environment_msg;
201  ret_val = ret_val && environment.verify(&environment_msg);
202  if (msg) *msg += environment_msg;
203  if (ret_val == false) return false; // we need all objects in environment allocated!
204 
205  // check reference dimension
206  if (environment.getController()->getStateDimension() != _xreference->getDimension())
207  {
208  ret_val = false;
209  if (msg)
210  *msg += "State reference trajectory dimension (" + std::to_string(_xreference->getDimension()) +
211  ") does not match controller state dimension (" + std::to_string(environment.getController()->getStateDimension()) + ").\n";
212  }
213  if (environment.getController()->getControlInputDimension() != _ureference->getDimension())
214  {
215  ret_val = false;
216  if (msg)
217  *msg += "Control reference trajectory dimension (" + std::to_string(_ureference->getDimension()) +
218  ") does not match controller control input dimension (" +
219  std::to_string(environment.getController()->getControlInputDimension()) + ").\n";
220  }
221 
222  if (environment.getPlant()->requiresFutureControls() && !environment.getController()->providesFutureControls())
223  {
224  ret_val = false;
225  if (msg) *msg += "Controller does not support control sequences, that are required by the plant";
226  }
227 
228  if (environment.getPlant()->requiresFutureStates() && !environment.getController()->providesFutureStates())
229  {
230  ret_val = false;
231  if (msg) *msg += "Controller does not support state sequences, that are required by the plant";
232  }
233 
234  return ret_val;
235 }
236 
237 #ifdef MESSAGE_SUPPORT
238 void OpenLoopControlTask::toMessage(corbo::messages::OpenLoopControlTask& message) const
239 {
240  message.set_dt(_dt);
241  message.set_realtime_sync(_realtime_sync);
242  if (_xreference) _xreference->toMessage(*message.mutable_xreference());
243  if (_ureference) _ureference->toMessage(*message.mutable_ureference());
244 }
245 void OpenLoopControlTask::fromMessage(const corbo::messages::OpenLoopControlTask& message, std::stringstream* issues)
246 {
247  _dt = message.dt();
248  _realtime_sync = message.realtime_sync();
249 
250  // xreference
251  _xreference.reset();
252  if (message.has_xreference())
253  {
254  // construct object
255  std::string type;
256  if (util::get_oneof_field_type(message.xreference(), "reference", type, false))
257  {
259  // import parameters
260  if (xreference)
261  {
262  xreference->fromMessage(message.xreference(), issues);
263  setStateReference(xreference);
264  }
265  }
266  }
267 
268  // ureference
269  _ureference.reset();
270  if (message.has_ureference())
271  {
272  // construct object
273  std::string type;
274  if (util::get_oneof_field_type(message.ureference(), "reference", type, false))
275  {
277  // import parameters
278  if (ureference)
279  {
280  ureference->fromMessage(message.ureference(), issues);
281  setControlReference(ureference);
282  }
283  }
284  }
285 }
286 #endif
287 
288 } // namespace corbo
corbo::OpenLoopControlTask::verify
bool verify(const Environment &environment, std::string *msg=nullptr) const override
Check if the environment and other settings satisfy all requirements for the given task.
Definition: task_open_loop_control.cpp:194
PRINT_FATAL
#define PRINT_FATAL(msg)
Print msg-stream as fatal error msg and exit program execution.
Definition: console.h:200
corbo::Time::now
static Time now()
Retrieve current system time.
Definition: time.h:297
corbo::TimeSeries::Interpolation
Interpolation
List of available interpolation methods.
Definition: time_series.h:102
PRINT_WARNING
#define PRINT_WARNING(msg)
Print msg-stream.
Definition: console.h:145
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::OpenLoopControlTask::_realtime_sync
bool _realtime_sync
Definition: task_open_loop_control.h:137
console.h
corbo::OpenLoopControlTask::_xreference
ReferenceTrajectoryInterface::Ptr _xreference
Definition: task_open_loop_control.h:138
corbo::TimeSeries::Interpolation::Linear
@ Linear
corbo::OpenLoopControlTask::performTask
void performTask(Environment &environment, SignalTargetInterface *signal_target=nullptr, std::string *msg=nullptr, const std::string &ns="") override
Perform task.
Definition: task_open_loop_control.cpp:88
corbo::OpenLoopControlTask::_ureference
ReferenceTrajectoryInterface::Ptr _ureference
Definition: task_open_loop_control.h:139
corbo::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
corbo::OpenLoopControlTask::OpenLoopControlTask
OpenLoopControlTask()
Default constructor.
Definition: task_open_loop_control.cpp:56
corbo::OpenLoopControlTask::getAvailableSignals
void getAvailableSignals(const Environment &environment, SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the task.
Definition: task_open_loop_control.cpp:63
corbo::Duration
Representation of time durations.
Definition: time.h:128
time.h
time_series.h
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::property::INHERITED
constexpr const int INHERITED
Inherit property.
Definition: core/include/corbo-core/types.h:84
corbo::ReferenceTrajectoryInterface::Ptr
std::shared_ptr< ReferenceTrajectoryInterface > Ptr
Definition: reference_trajectory.h:107
corbo::OpenLoopControlTask::setStateReference
void setStateReference(ReferenceTrajectoryInterface::Ptr xreference)
Set state reference trajectory.
Definition: task_open_loop_control.h:109
corbo::TimeSeries::Interpolation::ZeroOrderHold
@ ZeroOrderHold
task_open_loop_control.h
y
Scalar * y
Definition: level1_cplx_impl.h:102
utilities.h
corbo::Factory::create
std::shared_ptr< Derived > create(const std::string &name, bool print_error=true) const
Create a shared instance of the desired object.
Definition: factory.h:137
corbo::Time
Representation of time stamps.
Definition: time.h:273
corbo::OpenLoopControlTask::setControlReference
void setControlReference(ReferenceTrajectoryInterface::Ptr ureference)
Set control input reference trajectory.
Definition: task_open_loop_control.h:111
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:178
corbo::OpenLoopControlTask::_dt
double _dt
Definition: task_open_loop_control.h:136
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::ok
bool ok()
global method to check whether to proceed or cancel the current action
Definition: global.cpp:54
PRINT_INFO
#define PRINT_INFO(msg)
Print msg-stream.
Definition: console.h:117
corbo::TimeSeries::Extrapolation::ZeroOrderHold
@ ZeroOrderHold
PRINT_ERROR
#define PRINT_ERROR(msg)
Print msg-stream as error msg.
Definition: console.h:173


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