finite_differences_grid_se2.cpp
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 
24 
26 
27 #include <corbo-communication/utilities.h>
28 #include <corbo-core/console.h>
29 
30 #include <algorithm>
31 #include <cmath>
32 #include <memory>
33 
34 namespace mpc_local_planner {
35 
36 void FiniteDifferencesGridSE2::createEdges(NlpFunctions& nlp_fun, OptimizationEdgeSet& edges, SystemDynamicsInterface::Ptr dynamics)
37 {
38  assert(isValid());
39 
40  // clear edges first
41  // TODO(roesmann): we could implement a more efficient strategy without recreating the whole edgeset everytime
42  edges.clear();
43 
44  int n = getN();
45 
46  std::vector<BaseEdge::Ptr> cost_terms, eq_terms, ineq_terms;
47  for (int k = 0; k < n - 1; ++k)
48  {
49  VectorVertexSE2& x_next = (k < n - 2) ? _x_seq[k + 1] : _xf;
50  VectorVertex& u_prev = (k > 0) ? _u_seq[k - 1] : _u_prev;
51  ScalarVertex& dt_prev = (k > 0) ? _dt : _u_prev_dt;
52 
53  cost_terms.clear();
54  eq_terms.clear();
55  ineq_terms.clear();
56  nlp_fun.getNonIntegralStageFunctionEdges(k, _x_seq[k], _u_seq[k], _dt, u_prev, dt_prev, cost_terms, eq_terms, ineq_terms);
57  for (BaseEdge::Ptr& edge : cost_terms) edges.addObjectiveEdge(edge);
58  for (BaseEdge::Ptr& edge : eq_terms) edges.addEqualityEdge(edge);
59  for (BaseEdge::Ptr& edge : ineq_terms) edges.addInequalityEdge(edge);
60 
61  if (nlp_fun.stage_cost && nlp_fun.stage_cost->hasIntegralTerms(k))
62  {
64  {
66  std::make_shared<corbo::TrapezoidalIntegralCostEdge>(_x_seq[k], _u_seq[k], x_next, _dt, nlp_fun.stage_cost, k);
67  edges.addObjectiveEdge(edge);
68  }
70  {
71  corbo::LeftSumCostEdge::Ptr edge = std::make_shared<corbo::LeftSumCostEdge>(_x_seq[k], _u_seq[k], _dt, nlp_fun.stage_cost, k);
72  edges.addObjectiveEdge(edge);
73  }
74  else
75  PRINT_ERROR_NAMED("Cost integration rule not implemented");
76  }
77 
78  if (nlp_fun.stage_equalities && nlp_fun.stage_equalities->hasIntegralTerms(k))
79  {
81  {
82  corbo::TrapezoidalIntegralEqualityDynamicsEdge::Ptr edge = std::make_shared<corbo::TrapezoidalIntegralEqualityDynamicsEdge>(
83  dynamics, _x_seq[k], _u_seq[k], x_next, _dt, nlp_fun.stage_equalities, k);
84  edge->setFiniteDifferencesCollocationMethod(_fd_eval);
85  edges.addEqualityEdge(edge);
86  }
88  {
90  std::make_shared<corbo::LeftSumEqualityEdge>(_x_seq[k], _u_seq[k], _dt, nlp_fun.stage_equalities, k);
91  edges.addEqualityEdge(edge);
92 
93  // system dynamics edge
94  corbo::FDCollocationEdge::Ptr sys_edge = std::make_shared<corbo::FDCollocationEdge>(dynamics, _x_seq[k], _u_seq[k], x_next, _dt);
95  sys_edge->setFiniteDifferencesCollocationMethod(_fd_eval);
96  edges.addEqualityEdge(sys_edge);
97  }
98  else
99  PRINT_ERROR_NAMED("Cost integration rule not implemented");
100  }
101  else
102  {
103  // just the system dynamics edge
104  corbo::FDCollocationEdge::Ptr edge = std::make_shared<corbo::FDCollocationEdge>(dynamics, _x_seq[k], _u_seq[k], x_next, _dt);
105  edge->setFiniteDifferencesCollocationMethod(_fd_eval);
106  edges.addEqualityEdge(edge);
107  }
108 
109  if (nlp_fun.stage_inequalities && nlp_fun.stage_inequalities->hasIntegralTerms(k))
110  {
112  {
114  std::make_shared<corbo::TrapezoidalIntegralInequalityEdge>(_x_seq[k], _u_seq[k], x_next, _dt, nlp_fun.stage_inequalities, k);
115  edges.addInequalityEdge(edge);
116  }
118  {
120  std::make_shared<corbo::LeftSumInequalityEdge>(_x_seq[k], _u_seq[k], _dt, nlp_fun.stage_inequalities, k);
121  edges.addInequalityEdge(edge);
122  }
123  else
124  PRINT_ERROR_NAMED("Cost integration rule not implemented");
125  }
126  }
127 
128  // check if we have a separate unfixed final state
129  if (!_xf.isFixed())
130  {
131  // set final state cost
132  BaseEdge::Ptr cost_edge = nlp_fun.getFinalStateCostEdge(n - 1, _xf);
133  if (cost_edge) edges.addObjectiveEdge(cost_edge);
134 
135  // set final state constraint
136  BaseEdge::Ptr constr_edge = nlp_fun.getFinalStateConstraintEdge(n - 1, _xf);
137  if (constr_edge)
138  {
139  if (nlp_fun.final_stage_constraints->isEqualityConstraint())
140  edges.addEqualityEdge(constr_edge);
141  else
142  edges.addInequalityEdge(constr_edge);
143  }
144  }
145 
146  // add control deviation edges for last control
147  cost_terms.clear();
148  eq_terms.clear();
149  ineq_terms.clear();
150  nlp_fun.getFinalControlDeviationEdges(n, _u_ref, _u_seq.back(), _dt, cost_terms, eq_terms, ineq_terms);
151  for (BaseEdge::Ptr& edge : cost_terms) edges.addObjectiveEdge(edge);
152  for (BaseEdge::Ptr& edge : eq_terms) edges.addEqualityEdge(edge);
153  for (BaseEdge::Ptr& edge : ineq_terms) edges.addInequalityEdge(edge);
154 }
155 
156 } // namespace mpc_local_planner
corbo::DiscretizationGridInterface::_u_ref
VectorVertex _u_ref
PRINT_ERROR_NAMED
#define PRINT_ERROR_NAMED(msg)
corbo::TrapezoidalIntegralEqualityDynamicsEdge::Ptr
std::shared_ptr< TrapezoidalIntegralEqualityDynamicsEdge > Ptr
corbo::LeftSumInequalityEdge::Ptr
std::shared_ptr< LeftSumInequalityEdge > Ptr
mpc_local_planner::FullDiscretizationGridBaseSE2::_u_seq
std::vector< VectorVertex > _u_seq
Definition: full_discretization_grid_base_se2.h:249
corbo::LeftSumCostEdge::Ptr
std::shared_ptr< LeftSumCostEdge > Ptr
corbo::DiscretizationGridInterface::_u_prev_dt
ScalarVertex _u_prev_dt
mpc_local_planner::FullDiscretizationGridBaseSE2::CostIntegrationRule::TrapezoidalRule
@ TrapezoidalRule
mpc_local_planner
Definition: controller.h:44
console.h
corbo::FDCollocationEdge::Ptr
std::shared_ptr< FDCollocationEdge > Ptr
mpc_local_planner::FullDiscretizationGridBaseSE2::_xf
PartiallyFixedVectorVertexSE2 _xf
Definition: full_discretization_grid_base_se2.h:250
mpc_local_planner::FullDiscretizationGridBaseSE2::_dt
ScalarVertex _dt
Definition: full_discretization_grid_base_se2.h:258
mpc_local_planner::FullDiscretizationGridBaseSE2::_cost_integration
CostIntegrationRule _cost_integration
Definition: full_discretization_grid_base_se2.h:267
mpc_local_planner::FullDiscretizationGridBaseSE2::ScalarVertex
corbo::ScalarVertex ScalarVertex
Definition: full_discretization_grid_base_se2.h:114
corbo::BaseEdge::Ptr
std::shared_ptr< BaseEdge > Ptr
corbo::VertexInterface::isFixed
virtual bool isFixed() const
mpc_local_planner::FiniteDifferencesGridSE2::createEdges
void createEdges(NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics) override
Definition: finite_differences_grid_se2.cpp:56
corbo::TrapezoidalIntegralCostEdge::Ptr
std::shared_ptr< TrapezoidalIntegralCostEdge > Ptr
finite_differences_grid_se2.h
mpc_local_planner::FullDiscretizationGridBaseSE2::_fd_eval
corbo::FiniteDifferencesCollocationInterface::Ptr _fd_eval
Definition: full_discretization_grid_base_se2.h:246
mpc_local_planner::FullDiscretizationGridBaseSE2::VectorVertex
corbo::VectorVertex VectorVertex
Definition: full_discretization_grid_base_se2.h:115
mpc_local_planner::FullDiscretizationGridBaseSE2::getN
int getN() const override
get current horizon length
Definition: full_discretization_grid_base_se2.h:183
mpc_local_planner::FullDiscretizationGridBaseSE2::_x_seq
std::vector< VectorVertexSE2 > _x_seq
Definition: full_discretization_grid_base_se2.h:248
corbo::ScalarVertex::clear
void clear() override
mpc_local_planner::FullDiscretizationGridBaseSE2::CostIntegrationRule::LeftSum
@ LeftSum
n
PlainMatrixType mat * n
corbo::TrapezoidalIntegralInequalityEdge::Ptr
std::shared_ptr< TrapezoidalIntegralInequalityEdge > Ptr
mpc_local_planner::FullDiscretizationGridBaseSE2::isValid
virtual bool isValid() const
Definition: full_discretization_grid_base_se2.h:169
finite_differences_collocation_edges.h
corbo::DiscretizationGridInterface::_u_prev
VectorVertex _u_prev
corbo::LeftSumEqualityEdge::Ptr
std::shared_ptr< LeftSumEqualityEdge > Ptr


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06