dynamics_eval_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_DYNAMICS_EVAL_INTERFACE_H_
26 #define SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_DYNAMICS_EVAL_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
29 #include <corbo-core/range.h>
30 #include <corbo-core/types.h>
32 
33 #ifdef MESSAGE_SUPPORT
34 #include <corbo-communication/messages/numerics/dynamics_eval.pb.h>
35 #endif
36 
37 #include <functional>
38 #include <memory>
39 
40 namespace corbo {
41 
54 class DynamicsEvalInterface
55 {
56  public:
57  using Ptr = std::shared_ptr<DynamicsEvalInterface>;
58  using UPtr = std::unique_ptr<DynamicsEvalInterface>;
59 
60  using StateVector = Eigen::VectorXd;
61  using InputVector = Eigen::VectorXd;
62 
64  virtual ~DynamicsEvalInterface() {}
65 
67  virtual Ptr getInstance() const = 0;
68 
70  static Factory<DynamicsEvalInterface>& getFactory() { return Factory<DynamicsEvalInterface>::instance(); }
71 
88  virtual void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
89  const SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) = 0;
90 
93  const SystemDynamicsInterface& system, const Range& range, std::vector<Eigen::VectorXd>& states,
94  std::vector<Eigen::VectorXd>& controls) = 0;
95 
96  virtual bool interpolate(const std::vector<const Eigen::VectorXd*>& x, const std::vector<const Eigen::VectorXd*>& u, double dt,
97  const SystemDynamicsInterface& system, const Range& range, std::vector<Eigen::VectorXd>& states,
98  std::vector<Eigen::VectorXd>& controls)
99  {
100  if (x.size() > 1 && u.size() > 1)
101  return interpolate(*x[0], *u[0], *x.back(), *u.back(), dt, system, range, states, controls);
102  else if (x.size() > 1 && u.size() == 1)
103  return interpolate(*x[0], *u[0], *x.back(), *u[0], dt, system, range, states, controls);
104  PRINT_WARNING_NAMED("There is no appropriate overload for this method...");
105  return false;
106  }
107 
108 #ifdef MESSAGE_SUPPORT
109  virtual void toMessage(corbo::messages::DynamicsEval& message) const {}
112  virtual void fromMessage(const corbo::messages::DynamicsEval& message, std::stringstream* issues = nullptr) {}
113 #endif
114 };
115 
117 #define FACTORY_REGISTER_DYNAMICS_EVAL(type) FACTORY_REGISTER_OBJECT_ID(type, DynamicsEvalInterface, 0)
118 
119 } // namespace corbo
120 
121 #endif // SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_DYNAMICS_EVAL_INTERFACE_H_
PRINT_WARNING_NAMED
#define PRINT_WARNING_NAMED(msg)
Definition: console.h:255
system_dynamics_interface.h
factory.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::Factory
Generic factory object.
Definition: factory.h:90
corbo::DynamicsEvalInterface::interpolate
virtual bool interpolate(const Eigen::Ref< const Eigen::VectorXd > &x1, const Eigen::Ref< const Eigen::VectorXd > &u1, const Eigen::Ref< const Eigen::VectorXd > &x2, const Eigen::Ref< const Eigen::VectorXd > &u2, double dt, const SystemDynamicsInterface &system, const Range &range, std::vector< Eigen::VectorXd > &states, std::vector< Eigen::VectorXd > &controls)=0
corbo::DynamicsEvalInterface::getInstance
virtual Ptr getInstance() const =0
Return a newly allocated instances of the inherited class.
corbo::DynamicsEvalInterface::getFactory
static Factory< DynamicsEvalInterface > & getFactory()
Get access to the accociated factory.
Definition: dynamics_eval_interface.h:114
corbo::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
x
Scalar * x
Definition: level1_cplx_impl.h:89
range.h
corbo::DynamicsEvalInterface::StateVector
Eigen::VectorXd StateVector
Definition: dynamics_eval_interface.h:104
corbo::DynamicsEvalInterface::UPtr
std::unique_ptr< DynamicsEvalInterface > UPtr
Definition: dynamics_eval_interface.h:102
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
types.h
corbo::DynamicsEvalInterface::InputVector
Eigen::VectorXd InputVector
Definition: dynamics_eval_interface.h:105
corbo::DynamicsEvalInterface::computeEqualityConstraint
virtual void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error)=0
Compute error between two consecutive (discrete) states.
corbo::DynamicsEvalInterface::Ptr
std::shared_ptr< DynamicsEvalInterface > Ptr
Definition: dynamics_eval_interface.h:101
corbo::DynamicsEvalInterface::~DynamicsEvalInterface
virtual ~DynamicsEvalInterface()
Virtual destructor.
Definition: dynamics_eval_interface.h:108


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