collocation_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_COLLOCATION_INTERFACE_H_
26 #define SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_COLLOCATION_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
29 #include <corbo-core/time.h>
30 #include <corbo-core/types.h>
32 
33 #ifdef MESSAGE_SUPPORT
34 #include <corbo-communication/messages/numerics/collocation.pb.h>
35 #endif
36 
37 #include <functional>
38 #include <memory>
39 
40 namespace corbo {
41 
63 class CollocationInterface : public DynamicsEvalInterface
64 {
65  public:
66  using Ptr = std::shared_ptr<CollocationInterface>;
67  using UPtr = std::unique_ptr<CollocationInterface>;
68 
69  using StateVector = Eigen::VectorXd;
70  using InputVector = Eigen::VectorXd;
71 
73  virtual ~CollocationInterface() {}
75  DynamicsEvalInterface::Ptr getInstance() const override = 0;
76 
91  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
92  const SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override = 0;
93 
96  const SystemDynamicsInterface& system, const Range& range, std::vector<Eigen::VectorXd>& states,
97  std::vector<Eigen::VectorXd>& controls) override
98  {
99  if (range.getStart() < 0 || range.getEnd() > dt)
100  {
101  PRINT_ERROR_NAMED("range must be in the interval [0, dt]");
102  return false;
103  }
104 
105  states.push_back(x1);
106  controls.push_back(u1);
107 
108  if (dt < 1e-15) return true;
109 
110  int n = range.getNumInRange();
111  double t = range.getStart();
112  for (int i = 1; i < n; ++i, t += range.getStep())
113  {
114  double tau = (t - range.getStart()) / dt;
115  states.push_back(x1 + tau * (x2 - x1)); // linear state interpolation by default
116  controls.push_back(u1); // constant controls per default
117  }
118  if (range.includeEnd())
119  {
120  states.push_back(x2);
121  controls.push_back(u1);
122  }
123  return true;
124  }
125 
126 #ifdef MESSAGE_SUPPORT
127  // Implements interface method
128  virtual void toMessage(corbo::messages::Collocation& message) const {}
129  // Implements interface method
130  virtual void fromMessage(const corbo::messages::Collocation& message, std::stringstream* issues = nullptr) {}
131 
132  // Implements interface method
133  void toMessage(corbo::messages::DynamicsEval& message) const override { toMessage(*message.mutable_collocation()); }
134  // Implements interface method
135  void fromMessage(const corbo::messages::DynamicsEval& message, std::stringstream* issues = nullptr) override
136  {
137  if (message.has_collocation()) fromMessage(message.collocation());
138  }
139 #endif
140 };
141 
142 #define FACTORY_REGISTER_COLLOCATION(type) FACTORY_REGISTER_DYNAMICS_EVAL(type)
143 
144 } // namespace corbo
145 
146 #endif // SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_COLLOCATION_INTERFACE_H_
corbo::CollocationInterface::UPtr
std::unique_ptr< CollocationInterface > UPtr
Definition: collocation_interface.h:111
PRINT_ERROR_NAMED
#define PRINT_ERROR_NAMED(msg)
Definition: console.h:260
factory.h
corbo::CollocationInterface::InputVector
Eigen::VectorXd InputVector
Definition: collocation_interface.h:114
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::CollocationInterface::Ptr
std::shared_ptr< CollocationInterface > Ptr
Definition: collocation_interface.h:110
corbo::CollocationInterface::computeEqualityConstraint
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override=0
Compute differentiation error (system dynamics)
corbo::CollocationInterface::interpolate
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) override
Definition: collocation_interface.h:138
corbo::CollocationInterface::getInstance
DynamicsEvalInterface::Ptr getInstance() const override=0
Return a newly allocated instances of the inherited class.
time.h
corbo::CollocationInterface::~CollocationInterface
virtual ~CollocationInterface()
Virtual destructor.
Definition: collocation_interface.h:117
corbo::CollocationInterface::StateVector
Eigen::VectorXd StateVector
Definition: collocation_interface.h:113
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
dynamics_eval_interface.h
types.h
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::DynamicsEvalInterface::Ptr
std::shared_ptr< DynamicsEvalInterface > Ptr
Definition: dynamics_eval_interface.h:101


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