finite_differences_collocation.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_FINITE_DIFFERENCES_COLLOCATION_H_
26 #define SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_COLLOCATION_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/finite_differences_collocation.pb.h>
35 #endif
36 
37 #include <functional>
38 #include <memory>
39 
40 namespace corbo {
41 
61 {
62  public:
63  using Ptr = std::shared_ptr<FiniteDifferencesCollocationInterface>;
64  using UPtr = std::unique_ptr<FiniteDifferencesCollocationInterface>;
65 
66  using StateVector = Eigen::VectorXd;
67  using InputVector = Eigen::VectorXd;
68 
70  virtual ~FiniteDifferencesCollocationInterface() = default;
73 
76 
91  virtual void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
92  const SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) = 0;
93 
94 #ifdef MESSAGE_SUPPORT
95  virtual void toMessage(corbo::messages::FiniteDifferencesCollocation& message) const {}
97  // Message import
98  virtual void fromMessage(const corbo::messages::FiniteDifferencesCollocation& message, std::stringstream* issues = nullptr) {}
99 #endif
100 };
101 
103 #define FACTORY_REGISTER_FD_COLLOCATION(type) FACTORY_REGISTER_OBJECT(type, FiniteDifferencesCollocationInterface)
104 
120 {
121  public:
122  // Implements interface method
123  FiniteDifferencesCollocationInterface::Ptr getInstance() const override { return std::make_shared<ForwardDiffCollocation>(); }
124 
125  // Implements interface method
126  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
127  const SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override
128  {
129  assert(error.size() == x1.size());
130  // assert(dt > 0 && "dt must be greater then zero!");
131 
132  system.dynamics(x1, u1, error);
133  error -= (x2 - x1) / dt;
134  }
135 
136 };
138 
139 
154 {
155  public:
156  // Implements interface method
157  FiniteDifferencesCollocationInterface::Ptr getInstance() const override { return std::make_shared<BackwardDiffCollocation>(); }
158 
159  // Implements interface method
160  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
161  const SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override
162  {
163  assert(error.size() == x1.size());
164  assert(dt > 0 && "dt must be greater then zero!");
165 
166  system.dynamics(x2, u1, error);
167  error -= (x2 - x1) / dt;
168  }
169 
170 };
172 
173 
188 {
189  public:
190  // Implements interface method
191  FiniteDifferencesCollocationInterface::Ptr getInstance() const override { return std::make_shared<MidpointDiffCollocation>(); }
192 
193  // Implements interface method
194  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
195  const SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override
196  {
197  assert(error.size() == x1.size());
198  assert(dt > 0 && "dt must be greater then zero!");
199 
200  system.dynamics(0.5 * (x1 + x2), u1, error);
201  error -= (x2 - x1) / dt;
202  }
203 
204 };
206 
207 
222 {
223  public:
224  // Implements interface method
225  FiniteDifferencesCollocationInterface::Ptr getInstance() const override { return std::make_shared<CrankNicolsonDiffCollocation>(); }
226 
227  // Implements interface method
228  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
229  const SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override
230  {
231  assert(error.size() == x1.size());
232  assert(dt > 0 && "dt must be greater then zero!");
233 
234  Eigen::VectorXd f1(x1.size());
235  system.dynamics(x1, u1, f1);
236  system.dynamics(x2, u1, error);
237  error = (x2 - x1) / dt - 0.5 * (f1 + error);
238  }
239 
240 };
242 
243 } // namespace corbo
244 
245 #endif // SRC_NUMERICS_INCLUDE_CORBO_NUMERICS_FINITE_DIFFERENCES_COLLOCATION_H_
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute differentiation error (system dynamics)
Generic factory object.
Definition: factory.h:68
FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
virtual void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error)=0
Compute differentiation error (system dynamics)
Collocation via forward differences.
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute differentiation error (system dynamics)
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute differentiation error (system dynamics)
std::unique_ptr< FiniteDifferencesCollocationInterface > UPtr
#define FACTORY_REGISTER_FD_COLLOCATION(type)
static Factory< FiniteDifferencesCollocationInterface > & getFactory()
Get access to the associated factory.
virtual void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const =0
Evaluate the system dynamics equation.
Collocation via backward differences.
virtual ~FiniteDifferencesCollocationInterface()=default
Virtual destructor.
FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:72
FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
Interface class for system dynamic equations.
Collocation via Crank-Nicolson differences.
FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Return a newly allocated instances of the inherited class.
Collocation via midpoint differences.
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
Compute differentiation error (system dynamics)
Interface class for finite difference based collocation.
virtual FiniteDifferencesCollocationInterface::Ptr getInstance() const =0
Return a newly allocated instances of the inherited class.
std::shared_ptr< FiniteDifferencesCollocationInterface > Ptr


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