fd_collocation_se2.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020, Christoph Rösmann, All rights reserved.
6  *
7  * This program is free software: you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation, either version 3 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <https://www.gnu.org/licenses/>.
19  *
20  * Authors: Christoph Rösmann
21  *********************************************************************/
22 
23 #ifndef FINITE_DIFFERENCES_COLLOCATION_H_
24 #define FINITE_DIFFERENCES_COLLOCATION_H_
25 
27 
29 
30 #include <functional>
31 #include <memory>
32 
33 namespace mpc_local_planner {
34 
48 {
49  public:
50  // Implements interface method
51  corbo::FiniteDifferencesCollocationInterface::Ptr getInstance() const override { return std::make_shared<ForwardDiffCollocationSE2>(); }
52 
53  // Implements interface method
54  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
55  const corbo::SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override
56  {
57  assert(error.size() == x1.size());
58  assert(x1.size() >= 3);
59  // assert(dt > 0 && "dt must be greater then zero!");
60 
61  system.dynamics(x1, u1, error);
62  error.head(2) -= (x2.head(2) - x1.head(2)) / dt;
63  error.coeffRef(2) -= normalize_theta(x2.coeffRef(2) - x1.coeffRef(2)) / dt;
64  if (x1.size() > 3)
65  {
66  int n = x1.size() - 3;
67  error.tail(n) -= (x2.tail(n) - x1.tail(n)) / dt;
68  }
69  }
70 };
71 
85 {
86  public:
87  // Implements interface method
88  corbo::FiniteDifferencesCollocationInterface::Ptr getInstance() const override { return std::make_shared<MidpointDiffCollocationSE2>(); }
89 
90  // Implements interface method
91  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
92  const corbo::SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override
93  {
94  assert(error.size() == x1.size());
95  assert(dt > 0 && "dt must be greater then zero!");
96 
97  Eigen::VectorXd midpoint = 0.5 * (x1 + x2);
98  // fix angular component
99  midpoint.coeffRef(2) = interpolate_angle(x1.coeffRef(2), x2.coeffRef(2), 0.5);
100  system.dynamics(midpoint, u1, error);
101  error.head(2) -= (x2.head(2) - x1.head(2)) / dt;
102  error.coeffRef(2) -= normalize_theta(x2.coeffRef(2) - x1.coeffRef(2)) / dt;
103  if (x1.size() > 3)
104  {
105  int n = x1.size() - 3;
106  error.tail(n) -= (x2.tail(n) - x1.tail(n)) / dt;
107  }
108  }
109 };
110 
124 {
125  public:
126  // Implements interface method
127  corbo::FiniteDifferencesCollocationInterface::Ptr getInstance() const override { return std::make_shared<CrankNicolsonDiffCollocationSE2>(); }
128 
129  // Implements interface method
130  void computeEqualityConstraint(const StateVector& x1, const InputVector& u1, const StateVector& x2, double dt,
131  const corbo::SystemDynamicsInterface& system, Eigen::Ref<Eigen::VectorXd> error) override
132  {
133  assert(error.size() == x1.size());
134  assert(dt > 0 && "dt must be greater then zero!");
135 
136  Eigen::VectorXd f1(x1.size());
137  system.dynamics(x1, u1, f1);
138  system.dynamics(x2, u1, error);
139  // error = (x2 - x1) / dt - 0.5 * (f1 + error);
140  error.head(2) -= (x2.head(2) - x1.head(2)) / dt - 0.5 * (f1.head(2) + error.head(2));
141  error.coeffRef(2) -= normalize_theta(x2.coeffRef(2) - x1.coeffRef(2)) / dt - 0.5 * (f1.coeffRef(2) + error.coeffRef(2));
142  if (x1.size() > 3)
143  {
144  int n = x1.size() - 3;
145  error.tail(n) -= (x2.tail(n) - x1.tail(n)) / dt - 0.5 * (f1.tail(n) + error.tail(n));
146  }
147  }
148 };
149 
150 } // namespace mpc_local_planner
151 
152 #endif // FINITE_DIFFERENCES_COLLOCATION_H_
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const corbo::SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const corbo::SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
corbo::FiniteDifferencesCollocationInterface::Ptr getInstance() const override
corbo::FiniteDifferencesCollocationInterface::Ptr getInstance() const override
corbo::FiniteDifferencesCollocationInterface::Ptr getInstance() const override
Collocation via Crank-Nicolson differences (specialized for SE2)
virtual void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const=0
void computeEqualityConstraint(const StateVector &x1, const InputVector &u1, const StateVector &x2, double dt, const corbo::SystemDynamicsInterface &system, Eigen::Ref< Eigen::VectorXd > error) override
double interpolate_angle(double angle1, double angle2, double factor)
Return the interpolated angle between two angles [rad].
Definition: math_utils.h:100
Collocation via midpoint differences (specialized for SE2)
double normalize_theta(double theta)
normalize angle to interval [-pi, pi)
Definition: math_utils.h:81
Collocation via forward differences (specialized for SE2)
PlainMatrixType mat * n
std::shared_ptr< FiniteDifferencesCollocationInterface > Ptr


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:53:18