integrator_interface.h
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 
25 #ifndef SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_INTEGRATOR_INTERFACE_H_
26 #define SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_INTEGRATOR_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
29 #include <corbo-core/time.h>
30 #include <corbo-core/types.h>
33 
34 #ifdef MESSAGE_SUPPORT
35 #include <corbo-communication/messages/numerics/explicit_integrators.pb.h>
36 #endif
37 
38 #include <cmath>
39 #include <functional>
40 #include <memory>
41 
42 namespace corbo {
43 
45 // * @brief Interface for numerical integrators (explicit and implicit)
46 // *
47 // * @ingroup numerics
48 // *
49 // * Explicit numerical integrators in the context of ordinary or partial
50 // * differential equations determine the integral value only
51 // * based on the previous or current time instance, e.g.:
52 // * \f[
53 // * x(t_0 + \Delta t) = \int_{t_0}^{t_0+\Delta T} f(x(t_0), t) dt
54 // * \f].
55 // *
56 // * Implicit methods require the solution of a (nonlinear) equation, since
57 // * they also depend on the solution itself:
58 // * \f[
59 // * x(t_0 + \Delta t) = \int_{t_0}^{t_0+\Delta T} f(x(t_0+ \Delta T), x(t_0), t) dt
60 // * \f].
61 // *
62 // * This generic interface mainly provides access to the underlying quadrature rules.
63 // * These might be used as part of an optimization or might be solved via root-finding directly.
64 // * For a direct use of integrators you might refer to the subclass NumericalIntegratorExplicitInterface.
65 // *
66 // * @remark This interface is provided with factory support.
67 // *
68 // * @see NumericalIntegratorExplicitInterface FiniteDifferencesInterface
69 // *
70 // * @author Christoph Rösmann (christoph.roesmann@tu-dortmund.de)
71 // *
72 // * @todo This interface is not yet completed (messages, subclasses, ...)
73 // */
74 // class NumericalIntegratorInterface : public DynamicsEvalInterface
75 // {
76 // public:
77 // using Ptr = std::shared_ptr<NumericalIntegratorInterface>;
78 // using UPtr = std::unique_ptr<NumericalIntegratorInterface>;
79 //
80 // using StateVector = Eigen::VectorXd;
81 // using InputVector = Eigen::VectorXd;
82 // using UnaryFunction = const std::function<void(const Eigen::VectorXd&, Eigen::Ref<Eigen::VectorXd>)>;
83 //
84 // //! Virtual destructor
85 // virtual ~NumericalIntegratorInterface() {}
86 // //! Return a newly created shared instance of the implemented class
87 // virtual DynamicsEvalInterface::Ptr getInstance() const override = 0;
88 //
89 // /**
90 // * @brief Allocate memory for a given state dimension
91 // *
92 // * @remarks This method is optional and not guaranteed to be called, but if so this might speed up computation.
93 // * @param[in] state_dim Expected dimension of the state vector
94 // */
95 // virtual void initialize(int state_dim) {}
96 //
97 // /**
98 // * @brief Compute equality constraint containing the implicit quadrature/interpolation formula (system dynamics specialization)
99 // *
100 // * \f[
101 // * e = \int_{t=0}^{t=\Delta T} f(x(t), u_1) dt - x_2 = 0
102 // * \f].
103 // *
104 // * @param[in] x1 Initial state vector [SystemDynamicsInterface::getStateDimension() x 1]
105 // * @param[in] u1 Constant control input vector [SystemDynamicsInterface::getInputDimension() x 1]
106 // * @param[in] x2 Final state vector [SystemDynamicsInterface::getStateDimension() x 1]
107 // * @param[in] dt Time interval length
108 // * @param[in] system System dynamics object
109 // * @param[out] error Resulting error [SystemDynamicsInterface::getStateDimension() x 1] (must be preallocated)
110 // */
111 // void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt, const SystemDynamicsInterface&
112 // system,
113 // Eigen::Ref<Eigen::VectorXd> error) override = 0;
114 //
115 // /**
116 // * @brief Compute equality constraint containing the implicit quadrature/interpolation formula (unary function specialization)
117 // *
118 // * \f[
119 // * e = \int_{t=0}^{t=\Delta T} f(x(t)) dt - x_2 = 0
120 // * \f].
121 // *
122 // * @param[in] x1 Initial function argument
123 // * @param[in] x2 Final function argument
124 // * @param[in] dt Time interval length
125 // * @param[in] fun f(x) to be integrated in the interval [0, dt]
126 // * @param[out] error Resulting error [SystemDynamicsInterface::getStateDimension() x 1] (must be preallocated)
127 // */
128 // virtual void computeEqualityConstraint(const Eigen::Ref<const Eigen::VectorXd>& x1, const Eigen::Ref<const Eigen::VectorXd>& x2, double dt,
129 // const UnaryFunction& fun, Eigen::Ref<Eigen::VectorXd> error) = 0;
130 //
131 // #ifdef MESSAGE_SUPPORT
132 // virtual void toMessage(messages::Integrator& message) const
133 // {}
134 // virtual void fromMessage(const messages::Integrator& message, std::stringstream* issues = nullptr) {}
135 // #endif
136 // };
137 //
138 // #define FACTORY_REGISTER_INTEGRATOR(type) FACTORY_REGISTER_DYNAMICS_EVAL(type)
139 
159 {
160  public:
161  using Ptr = std::shared_ptr<NumericalIntegratorExplicitInterface>;
162  using UPtr = std::unique_ptr<NumericalIntegratorExplicitInterface>;
163 
164  using UnaryFunction = const std::function<void(const Eigen::VectorXd&, Eigen::Ref<Eigen::VectorXd>)>;
165  // using DynamicsEvalInterface::StateVector;
166  // using DynamicsEvalInterface::InputVector;
167 
171  DynamicsEvalInterface::Ptr getInstance() const override = 0;
172 
174  virtual int getConvergenceOrder() const = 0;
175 
182  virtual void initialize(int state_dim) {}
183 
198  virtual void solveIVP(const Eigen::VectorXd& x1, double dt, const UnaryFunction& fun, Eigen::Ref<Eigen::VectorXd> x2) = 0;
199 
214  virtual void solveIVP(const StateVector& x1, const InputVector& u1, double dt, const SystemDynamicsInterface& system,
216 
217  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
218  const SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override
219  {
220  solveIVP(x1, u1, dt, system, error);
221  error -= x2;
222  }
223 
225  const UnaryFunction& fun, Eigen::Ref<Eigen::VectorXd> error)
226  {
227  solveIVP(x1, dt, fun, error);
228  error -= x2;
229  }
230 
232  const Eigen::Ref<const Eigen::VectorXd>& /*x2*/, const Eigen::Ref<const Eigen::VectorXd>& /*u2*/, double dt,
233  const SystemDynamicsInterface& system, const Range& range, std::vector<Eigen::VectorXd>& states,
234  std::vector<Eigen::VectorXd>& controls) override
235  {
236  if (range.getStart() < 0 || range.getEnd() > dt)
237  {
238  PRINT_ERROR_NAMED("range must be in the interval [0, dt]");
239  return false;
240  }
241  if (dt < 1e-15)
242  {
243  states.push_back(x1);
244  controls.push_back(u1);
245  return true;
246  }
247 
248  Eigen::VectorXd x_cur = x1;
249  Eigen::VectorXd x_next(x1.size());
250 
251  int n = range.getNumInRange();
252  for (int i = 0; i < n; ++i)
253  {
254  states.push_back(x_cur);
255  controls.push_back(u1); // constant controls per default
256 
257  if (i < n - 1)
258  {
259  solveIVP(x_cur, u1, range.getStep(), system, x_next);
260  }
261  x_cur = x_next;
262  }
263 
264  if (range.includeEnd())
265  {
266  solveIVP(x_cur, u1, range.getRemainder(), system, x_next);
267  }
268  return true;
269  }
270 
271 #ifdef MESSAGE_SUPPORT
272  virtual void toMessage(messages::ExplicitIntegrator& message) const {}
275  virtual void fromMessage(const messages::ExplicitIntegrator& message, std::stringstream* issues = nullptr) {}
276 
278  // void toMessage(corbo::messages::Integrator& message) const override { toMessage(*message.mutable_explicit_integrator()); }
280  // void fromMessage(const corbo::messages::Integrator& message, std::stringstream* issues = nullptr) override
281  //{
282  // if (message.has_explicit_integrator()) fromMessage(message.explicit_integrator());
283  //}
284 
286  void toMessage(corbo::messages::DynamicsEval& message) const override { toMessage(*message.mutable_integrator()); }
288  void fromMessage(const corbo::messages::DynamicsEval& message, std::stringstream* issues = nullptr) override
289  {
290  if (message.has_integrator()) fromMessage(message.integrator());
291  }
292 #endif
293 };
294 
295 // #define FACTORY_REGISTER_EXPLICIT_INTEGRATOR(type) FACTORY_REGISTER_INTEGRATOR(type)
296 #define FACTORY_REGISTER_EXPLICIT_INTEGRATOR(type) FACTORY_REGISTER_DYNAMICS_EVAL(type)
297 
298 // class NumericalIntegratorImplicitInterface : public NumericalIntegratorInterface
299 // {
300 // public:
301 // using Ptr = std::shared_ptr<NumericalIntegratorImplicitInterface>;
302 // using UPtr = std::unique_ptr<NumericalIntegratorImplicitInterface>;
303 //
304 // //! Virtual destructor
305 // virtual ~NumericalIntegratorImplicitInterface() {}
306 // //! Return a newly created shared instance of the implemented class
307 // virtual DynamicsEvalInterface::Ptr getInstance() const override = 0;
308 //
309 // /**
310 // * @brief Allocate memory for a given state dimension
311 // *
312 // * @remarks This method is optional and not guaranteed to be called, but if so this might speed up computation.
313 // * @param[in] state_dim Expected dimension of the state vector
314 // */
315 // //virtual void initialize(int state_dim) {}
316 //
317 //
318 // virtual void quadrature(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt, const SystemDynamicsInterface& system,
319 // Eigen::Ref<Eigen::VectorXd> integral_value) = 0;
320 //
321 // // integral of x(t) over the interval [0, dt]
322 // virtual void quadrature(const Eigen::Ref<const Eigen::VectorXd>& x1, const Eigen::Ref<const Eigen::VectorXd>& x2, double dt, const
323 // UnaryFunction& fun,
324 // Eigen::Ref<Eigen::VectorXd> integral_value) = 0;
325 //
326 // void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt, const SystemDynamicsInterface&
327 // system,
328 // Eigen::Ref<Eigen::VectorXd> error) override
329 // {
330 // quadrature(x1, u1, x2, dt, system, error);
331 // error -= x2;
332 // }
333 //
334 // void computeEqualityConstraint(const Eigen::Ref<const Eigen::VectorXd>& x1, const Eigen::Ref<const Eigen::VectorXd>& x2, double dt,
335 // const UnaryFunction& fun, Eigen::Ref<Eigen::VectorXd> error) override
336 // {
337 // quadrature(x1, x2, dt, fun, error);
338 // error -= x2;
339 // }
340 //
341 // #ifdef MESSAGE_SUPPORT
342 // //! Export integrator settings to message
343 // virtual void toMessage(messages::ImplicitIntegrator& message) const {}
344 // //! Import integrator settings from message
345 // virtual void fromMessage(const messages::ImplicitIntegrator& message, std::stringstream* issues = nullptr) {}
346 //
347 // //! Export selected class and parameters to a Integrator message
348 // void toMessage(corbo::messages::Integrator& message) const override { toMessage(*message.mutable_implicit_integrator()); }
349 // //! Import selected class and parameters from a Integrator message (optionally pass any issues to the caller).
350 // void fromMessage(const corbo::messages::Integrator& message, std::stringstream* issues = nullptr) override
351 // {
352 // if (message.has_explicit_integrator()) fromMessage(message.implicit_integrator());
353 // }
354 //
355 // //! Export selected class and parameters to a DynamicsEval message
356 // //void toMessage(corbo::messages::DynamicsEval& message) const override { toMessage(*message.mutable_integrator()); }
357 // //! Import selected class and parameters from a DynamicsEval message (optionally pass any issues to the caller).
358 // //void fromMessage(const corbo::messages::DynamicsEval& message, std::stringstream* issues = nullptr) override
359 // //{
360 // // if (message.has_integrator()) fromMessage(message.integrator());
361 // //}
362 // #endif
363 // };
364 //
365 // #define FACTORY_REGISTER_IMPLICIT_INTEGRATOR(type) FACTORY_REGISTER_INTEGRATOR(type)
366 
367 } // namespace corbo
368 
369 #endif // SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_INTEGRATOR_INTERFACE_H_
#define PRINT_ERROR_NAMED(msg)
Definition: console.h:260
int getNumInRange() const
Definition: range.h:71
double getStart() const
Definition: range.h:62
virtual void solveIVP(const Eigen::VectorXd &x1, double dt, const UnaryFunction &fun, Eigen::Ref< Eigen::VectorXd > x2)=0
Solution of the initial value problem.
Interface for numerical integrators (explicit and implicit)
double getEnd() const
Definition: range.h:64
DynamicsEvalInterface::Ptr getInstance() const override=0
Return a newly created shared instance of the implemented class.
virtual void initialize(int state_dim)
Allocate memory for a given state dimension.
virtual ~NumericalIntegratorExplicitInterface()
Virtual destructor.
double getStep() const
Definition: range.h:63
bool includeEnd() const
Definition: range.h:66
std::shared_ptr< DynamicsEvalInterface > Ptr
virtual int getConvergenceOrder() const =0
Return the convergence order.
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute error between two consecutive (discrete) states.
const std::function< void(const Eigen::VectorXd &, Eigen::Ref< Eigen::VectorXd >)> UnaryFunction
Interface class for solving and evaluating dynamics.
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
std::unique_ptr< DynamicsEvalInterface > UPtr
Interface class for system dynamic equations.
bool interpolate(const Eigen::Ref< const Eigen::VectorXd > &x1, const Eigen::Ref< const Eigen::VectorXd > &u1, const Eigen::Ref< const Eigen::VectorXd > &, const Eigen::Ref< const Eigen::VectorXd > &, double dt, const SystemDynamicsInterface &system, const Range &range, std::vector< Eigen::VectorXd > &states, std::vector< Eigen::VectorXd > &controls) override
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
double getRemainder() const
Definition: range.h:69
void computeEqualityConstraint(const Eigen::Ref< const Eigen::VectorXd > &x1, const Eigen::Ref< const Eigen::VectorXd > &x2, double dt, const UnaryFunction &fun, Eigen::Ref< Eigen::VectorXd > error)


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:06:54