one_step_predictor.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 
28 
29 namespace corbo {
30 
31 double OneStepPredictor::getDeadTime() { return _dynamics ? _dynamics->getDeadTime() : 0.0; }
32 
34 {
35  if (!_dynamics || !_integrator) return false;
36 
37  _initialized = true;
38 
39  return true;
40 }
41 
42 void OneStepPredictor::predict(const Eigen::Ref<const StateVector>& x0, std::vector<std::pair<double, ControlVector>> u_seq, double dt,
44 {
45  if (dt <= 0)
46  {
47  x1 = x0;
48  return;
49  }
50 
51  if (!_initialized) initialize();
52 
53  if (x1.rows() != x0.rows())
54  {
55  PRINT_ERROR_NAMED("size of x1 does not match size of x0. Aborting.");
56  return;
57  }
58 
59  Eigen::VectorXd x = x0;
60 
61  for (int i = 0; i < u_seq.size(); ++i)
62  {
63  double cur_dt = u_seq[i].first;
64 
65  if (_dynamics->isContinuousTime())
66  {
67  // _integrator->integrate(_current_state, u, dt.toSec(), *_dynamics, next_state);
68  _integrator->solveIVP(x, u_seq[i].second, cur_dt, *_dynamics, x1);
69  }
70  else
71  {
72  // TODO(roesmann): we need to check how discrete states behave with the deadtime simulator!!!
73  PRINT_WARNING_COND(_dynamics->getDeadTime() > 0, "Discrete-time systems with deadtime not yet tested/fully implemented...");
74  _dynamics->dynamics(x, u_seq[i].second, x1);
75  }
76  x = x1; // TODO(roesmann): place for improving efficiency (this is not required in the last step...)
77  }
78 }
79 
81 
82 #ifdef MESSAGE_SUPPORT
83 void OneStepPredictor::toMessage(messages::OneStepPredictor& message) const
84 {
85  if (_dynamics) _dynamics->toMessage(*message.mutable_system_dynamics());
86  if (_integrator) _integrator->toMessage(*message.mutable_integrator());
87 }
88 
89 void OneStepPredictor::fromMessage(const messages::OneStepPredictor& message, std::stringstream* issues)
90 {
91  _dynamics.reset();
92  _integrator.reset();
93 
94  // system dynamics
95  if (message.has_system_dynamics())
96  {
97  // construct object
98  std::string type;
99  util::get_oneof_field_type_expand_isolated(message.system_dynamics(), "system_dynamics", type, false, 1);
101  // import parameters
102  if (dynamics)
103  {
104  dynamics->fromMessage(message.system_dynamics(), issues);
105  setSystemDynamics(dynamics);
106  }
107  }
108 
109  // integrator
110  if (message.has_integrator())
111  {
112  // construct object
113  std::string type;
114  util::get_oneof_field_type(message.integrator(), "explicit_integrator", type, false);
115  NumericalIntegratorExplicitInterface::Ptr integrator = create_from_factory<NumericalIntegratorExplicitInterface>(type);
116  // import parameters
117  if (integrator)
118  {
119  integrator->fromMessage(message.integrator(), issues);
120  setIntegrator(integrator);
121  }
122  }
123 }
124 #endif
125 
126 } // namespace corbo
PRINT_ERROR_NAMED
#define PRINT_ERROR_NAMED(msg)
Definition: console.h:260
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::NumericalIntegratorExplicitInterface::Ptr
std::shared_ptr< NumericalIntegratorExplicitInterface > Ptr
Definition: integrator_interface.h:205
corbo::OneStepPredictor::initialize
bool initialize()
initialize the predictor
Definition: one_step_predictor.cpp:55
corbo::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
corbo::OneStepPredictor::predict
void predict(const Eigen::Ref< const StateVector > &x0, std::vector< std::pair< double, ControlVector >> u_seq, double dt, Eigen::Ref< StateVector > x1)
Predict x1 using t0, x0, u and dt (alias between x0 and x1 allowed)
Definition: one_step_predictor.cpp:64
corbo::OneStepPredictor::setIntegrator
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Set a numerical integrator for continuous-time dynamics.
Definition: one_step_predictor.h:113
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::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
utilities.h
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
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::OneStepPredictor::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: one_step_predictor.h:123
corbo::OneStepPredictor::getDeadTime
double getDeadTime()
Definition: one_step_predictor.cpp:53
corbo::OneStepPredictor::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: one_step_predictor.h:124
one_step_predictor.h
corbo::OneStepPredictor::setSystemDynamics
void setSystemDynamics(SystemDynamicsInterface::Ptr dynamics)
Set the system dynamics of the simulated plant.
Definition: one_step_predictor.cpp:102
corbo::OneStepPredictor::_initialized
bool _initialized
Definition: one_step_predictor.h:126


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