multiple_shooting_grid.cpp
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 
26 
28 
30 #include <corbo-core/console.h>
31 
32 #include <algorithm>
33 #include <cmath>
34 #include <memory>
35 
36 namespace corbo {
37 
38 void MultipleShootingGrid::createEdges(NlpFunctions& nlp_fun, OptimizationEdgeSet& edges, SystemDynamicsInterface::Ptr dynamics)
39 {
40  assert(isValid());
41  assert(_integrator);
42 
43  // clear edges first
44  // TODO(roesmann): we could implement a more efficient strategy without recreating the whole edgeset everytime
45  edges.clear();
46 
47  int n = getN();
48 
49  std::vector<BaseEdge::Ptr> cost_terms, eq_terms, ineq_terms;
50  int k = 0;
51  for (int i = 0; i < (int)_intervals.size(); ++i)
52  {
53  VectorVertex& s = _intervals[i].s;
54  VectorVertex& s_next = (i < (int)_intervals.size() - 1) ? _intervals[i + 1].s : _xf;
55  std::vector<VectorVertex>& u_seq = _intervals[i].u_seq;
56  VectorVertex& u_prev = (i == 0) ? _u_prev : _intervals[i - 1].u_seq.back(); // TODO(roesmann): add also to other grids...
57  ScalarVertex& dt_prev = (i == 0) ? _u_prev_dt : _dt;
58 
59  if (u_seq.size() == 1)
60  {
61  // full discretization
62  cost_terms.clear();
63  eq_terms.clear();
64  ineq_terms.clear();
65  nlp_fun.getNonIntegralStageFunctionEdges(k, s, u_seq.front(), _dt, u_prev, dt_prev, cost_terms, eq_terms, ineq_terms);
66  for (BaseEdge::Ptr& edge : cost_terms) edges.addObjectiveEdge(edge);
67  for (BaseEdge::Ptr& edge : eq_terms) edges.addEqualityEdge(edge);
68  for (BaseEdge::Ptr& edge : ineq_terms) edges.addInequalityEdge(edge);
69 
70  if (nlp_fun.hasIntegralTerms(k))
71  {
72  // system dynamics and integral cost/constraints
73  MultipleShootingEdgeSingleControl::Ptr edge = std::make_shared<MultipleShootingEdgeSingleControl>(
74  dynamics, nlp_fun.stage_cost, nlp_fun.stage_equalities, nlp_fun.stage_inequalities, k, s, u_seq.front(), _dt, s_next);
75  edge->setIntegrator(_integrator);
76  edges.addMixedEdge(edge);
77  }
78  else
79  {
80  // system dynamics
81  MSVariableDynamicsOnlyEdge::Ptr edge = std::make_shared<MSVariableDynamicsOnlyEdge>(
82  dynamics, s, u_seq.front(), s_next, _dt); // TODO(roesmann): this is version that allows a variable dt
83  edge->setIntegrator(_integrator);
84  edges.addEqualityEdge(edge);
85  }
86  }
87  else
88  {
89  // TODO(roesmann): maybe we are forgetting to evaluate non-integral stage functions at non-shooting grid points?? -> Check (
90  // it seems so according to a quick simulation...: quadratic form cost (non-integral)
91 
92  int num_controls = (int)u_seq.size();
93 
94  if (nlp_fun.hasIntegralTerms(k) || _intermediate_x_constraints)
95  {
97  std::make_shared<MultipleShootingEdge>(dynamics, nlp_fun.stage_cost, nlp_fun.stage_equalities, nlp_fun.stage_inequalities, k,
98  num_controls + 1, num_controls, // TODO(roesmann): here could use a different nc
100  edge->setIntegrator(_integrator);
101 
102  edge->setVertex(0, s);
103  edge->setVertex(1, s_next);
104  int vert_idx = 2;
105  for (int i = 0; i < num_controls; ++i)
106  {
107  edge->setVertex(vert_idx++, u_seq[i]);
108  }
109  edge->setVertex(vert_idx++, _dt);
110  edge->finalize();
111  edges.addMixedEdge(edge);
112  }
113  else
114  {
115  // dynamics only
116  MSDynamicsOnlyMultiControlsEdge::Ptr edge = std::make_shared<MSDynamicsOnlyMultiControlsEdge>(dynamics, num_controls);
117  edge->setIntegrator(_integrator);
118 
119  edge->setVertex(0, s);
120  edge->setVertex(1, s_next);
121  edge->setVertex(2, _dt);
122  for (int i = 0; i < num_controls; ++i)
123  {
124  edge->setVertex(3 + i, u_seq[i]);
125  }
126  edge->finalize();
127  edges.addEqualityEdge(edge);
128  }
129 
130  // add non-integral terms at shooting nodes
131  cost_terms.clear();
132  eq_terms.clear();
133  ineq_terms.clear();
134  nlp_fun.getNonIntegralStageFunctionEdges(k, s, u_seq.front(), _dt, u_prev, dt_prev, cost_terms, eq_terms, ineq_terms);
135  for (BaseEdge::Ptr& edge : cost_terms) edges.addObjectiveEdge(edge);
136  for (BaseEdge::Ptr& edge : eq_terms) edges.addEqualityEdge(edge);
137  for (BaseEdge::Ptr& edge : ineq_terms) edges.addInequalityEdge(edge);
138 
139  // also add terms that depend only on controls and dts to the interval variables (skip first ones since they are considered above)
140  for (int i = 1; i < (int)u_seq.size(); ++i)
141  {
142  // VectorVertex& ukk = i < (int)u_seq.size() ? u_seq[i] : *interval.controls.back(); // ith control of the shooting interval -> for
143  // move blocking
144 
145  if (nlp_fun.stage_cost)
146  {
147  cost_terms.clear();
148  getStageFunctionEdgesIntermediateControlDtMultipleShooting(k + i, u_seq[i], _dt, u_prev, dt_prev, *nlp_fun.stage_cost,
149  cost_terms);
150  for (BaseEdge::Ptr& edge : cost_terms) edges.addObjectiveEdge(edge);
151  }
152  if (nlp_fun.stage_equalities)
153  {
154  eq_terms.clear();
155  getStageFunctionEdgesIntermediateControlDtMultipleShooting(k + i, u_seq[i], _dt, u_prev, dt_prev, *nlp_fun.stage_equalities,
156  eq_terms);
157  for (BaseEdge::Ptr& edge : eq_terms) edges.addEqualityEdge(edge);
158  }
159  if (nlp_fun.stage_inequalities)
160  {
161  ineq_terms.clear();
162  getStageFunctionEdgesIntermediateControlDtMultipleShooting(k + i, u_seq[i], _dt, u_prev, dt_prev, *nlp_fun.stage_inequalities,
163  ineq_terms);
164  for (BaseEdge::Ptr& edge : ineq_terms) edges.addInequalityEdge(edge);
165  }
166  }
167  }
168  k += (int)u_seq.size();
169  }
170 
171  // check if we have a separate unfixed final state
172  if (!_xf.isFixed())
173  {
174  // set final state cost
175  BaseEdge::Ptr cost_edge = nlp_fun.getFinalStateCostEdge(n - 1, _xf);
176  if (cost_edge) edges.addObjectiveEdge(cost_edge);
177 
178  // set final state constraint
179  BaseEdge::Ptr constr_edge = nlp_fun.getFinalStateConstraintEdge(n - 1, _xf);
180  if (constr_edge)
181  {
182  if (nlp_fun.final_stage_constraints->isEqualityConstraint())
183  edges.addEqualityEdge(constr_edge);
184  else
185  edges.addInequalityEdge(constr_edge);
186  }
187  }
188 
189  // add control deviation edges for last control
190  cost_terms.clear();
191  eq_terms.clear();
192  ineq_terms.clear();
193  nlp_fun.getFinalControlDeviationEdges(n, _u_ref, _intervals.back().u_seq.back(), _dt, cost_terms, eq_terms, ineq_terms);
194  for (BaseEdge::Ptr& edge : cost_terms) edges.addObjectiveEdge(edge);
195  for (BaseEdge::Ptr& edge : eq_terms) edges.addEqualityEdge(edge);
196  for (BaseEdge::Ptr& edge : ineq_terms) edges.addInequalityEdge(edge);
197 }
198 
199 void MultipleShootingGrid::getStageFunctionEdgesIntermediateControlDtMultipleShooting(int k, VectorVertex& uk, ScalarVertex& dt, VectorVertex& u_prev,
200  ScalarVertex& dt_prev, const StageFunction& stage_fun,
201  std::vector<BaseEdge::Ptr>& edges)
202 {
203  int dim = stage_fun.getNonIntegralControlTermDimension(k);
204  if (dim > 0)
205  {
206  using Edge = UnaryVectorVertexEdge<StageFunction, &StageFunction::computeNonIntegralControlTerm>;
207  Edge::Ptr edge =
208  std::make_shared<Edge>(dim, k, stage_fun, uk, stage_fun.isLinearNonIntegralControlTerm(k), stage_fun.isLsqFormNonIntegralControlTerm(k));
209  edges.push_back(edge);
210  }
211 
212  dim = stage_fun.getNonIntegralDtTermDimension(k);
213  if (dim > 0)
214  {
215  using Edge = UnaryScalarVertexEdge<StageFunction, &StageFunction::computeNonIntegralDtTerm>;
216  Edge::Ptr edge =
217  std::make_shared<Edge>(dim, k, stage_fun, dt, stage_fun.isLinearNonIntegralDtTerm(k), stage_fun.isLsqFormNonIntegralDtTerm(k));
218  edges.push_back(edge);
219  }
220 
221  dim = stage_fun.getNonIntegralControlDeviationTermDimension(k);
222  if (dim > 0)
223  {
225  Edge::Ptr edge = std::make_shared<Edge>(dim, k, stage_fun, uk, u_prev, dt_prev, false, false);
226  edges.push_back(edge);
227  }
228 }
229 
230 #ifdef MESSAGE_SUPPORT
231 void MultipleShootingGrid::fromMessage(const messages::MultipleShootingGrid& message, std::stringstream* issues)
232 {
233  if (message.n() < 2 && issues) *issues << "MultipleShootingGrid: Number of states must be greater than or equal 2.\n";
234  if (message.dt() <= 0 && issues) *issues << "MultipleShootingGrid: Dt must be greater than 0.0.\n";
235 
236  setNRef(message.n());
237  setDtRef(message.dt());
238  setNumControlsPerShootingInterval(message.num_u_per_interval(), message.intermediate_x_constraints());
239  setWarmStart(message.warm_start());
240 
241  // fd collocation method
242  // construct object
243  std::string type;
244  util::get_oneof_field_type(message.integrator(), "explicit_integrator", type, false);
245  NumericalIntegratorExplicitInterface::Ptr integrator = create_from_factory<NumericalIntegratorExplicitInterface>(type);
246  // import parameters
247  if (integrator)
248  {
249  integrator->fromMessage(message.integrator(), issues);
250  setNumericalIntegrator(integrator);
251  }
252  else
253  {
254  if (issues) *issues << "MultipleShootingGrid: unknown integration method specified.\n";
255  return;
256  }
257 }
258 
259 void MultipleShootingGrid::toMessage(messages::MultipleShootingGrid& message) const
260 {
261  message.set_n(getNRef());
262  message.set_dt(getDtRef());
263  message.set_num_u_per_interval(_num_u_per_interv_ref);
264  message.set_intermediate_x_constraints(_intermediate_x_constraints);
265  message.set_warm_start(_warm_start);
266 
267  // fd collocation method
268  if (_integrator) _integrator->fromMessage(*message.mutable_integrator());
269 }
270 #endif
271 
272 } // namespace corbo
corbo::DiscretizationGridInterface::_u_ref
VectorVertex _u_ref
Definition: discretization_grid_interface.h:192
corbo::ShootingGridBase::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: shooting_grid_base.h:194
corbo::ShootingGridBase::setDtRef
void setDtRef(double dt)
Definition: shooting_grid_base.h:143
corbo::ShootingGridBase::_num_u_per_interv_ref
int _num_u_per_interv_ref
Definition: shooting_grid_base.h:201
corbo::ShootingGridBase::_intervals
std::vector< ShootingInterval > _intervals
Definition: shooting_grid_base.h:196
corbo::MultipleShootingGrid::getStageFunctionEdgesIntermediateControlDtMultipleShooting
void getStageFunctionEdgesIntermediateControlDtMultipleShooting(int k, VectorVertex &uk, ScalarVertex &dt, VectorVertex &u_prev, ScalarVertex &dt_prev, const StageFunction &stage_fun, std::vector< BaseEdge::Ptr > &edges)
Definition: multiple_shooting_grid.cpp:221
corbo::ShootingGridBase::setWarmStart
void setWarmStart(bool active)
Definition: shooting_grid_base.h:146
s
RealScalar s
Definition: level1_cplx_impl.h:104
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::NumericalIntegratorExplicitInterface::Ptr
std::shared_ptr< NumericalIntegratorExplicitInterface > Ptr
Definition: integrator_interface.h:205
corbo::DiscretizationGridInterface::_u_prev_dt
ScalarVertex _u_prev_dt
Definition: discretization_grid_interface.h:191
corbo::MSVariableDynamicsOnlyEdge::Ptr
std::shared_ptr< MSVariableDynamicsOnlyEdge > Ptr
Definition: multiple_shooting_edges.h:122
console.h
multiple_shooting_edges.h
corbo::MSDynamicsOnlyMultiControlsEdge::Ptr
std::shared_ptr< MSDynamicsOnlyMultiControlsEdge > Ptr
Definition: multiple_shooting_edges.h:844
corbo::ShootingGridBase::_xf
PartiallyFixedVectorVertex _xf
Definition: shooting_grid_base.h:198
corbo::ShootingGridBase::_warm_start
bool _warm_start
Definition: shooting_grid_base.h:206
corbo::TernaryVectorScalarVertexEdge
Definition: generic_edge.h:473
corbo::ShootingGridBase::getN
int getN() const override
Definition: shooting_grid_base.cpp:423
corbo::BaseEdge::Ptr
std::shared_ptr< BaseEdge > Ptr
Definition: edge_interface.h:134
corbo::MultipleShootingEdge::Ptr
std::shared_ptr< MultipleShootingEdge > Ptr
Definition: multiple_shooting_edges.h:502
corbo::VertexInterface::isFixed
virtual bool isFixed() const
Check if all components are fixed.
Definition: vertex_interface.h:91
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
corbo::MultipleShootingGrid::createEdges
void createEdges(NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics) override
Definition: multiple_shooting_grid.cpp:60
multiple_shooting_grid.h
corbo::MultipleShootingEdgeSingleControl::Ptr
std::shared_ptr< MultipleShootingEdgeSingleControl > Ptr
Definition: multiple_shooting_edges.h:176
int
return int(ret)+1
corbo::ShootingGridBase::getDtRef
double getDtRef() const
Definition: shooting_grid_base.h:144
utilities.h
corbo::ShootingGridBase::setNumericalIntegrator
void setNumericalIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: shooting_grid_base.h:150
corbo::Edge::Ptr
std::shared_ptr< Edge > Ptr
Definition: edge.h:195
corbo::ShootingGridBase::setNRef
void setNRef(int n)
Definition: shooting_grid_base.cpp:434
corbo::ScalarVertex::clear
void clear() override
Clear complete backup container.
Definition: scalar_vertex.h:220
corbo::ShootingGridBase::isValid
bool isValid() const
Definition: shooting_grid_base.h:123
corbo::ShootingGridBase::_dt
ScalarVertex _dt
Definition: shooting_grid_base.h:197
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::Edge
Templated base edge class that stores an arbitary number of value.
Definition: edge.h:170
corbo::ShootingGridBase::setNumControlsPerShootingInterval
void setNumControlsPerShootingInterval(int num_u_per_interv)
Definition: shooting_grid_base.h:136
corbo::ShootingGridBase::getNRef
int getNRef() const
Definition: shooting_grid_base.h:134
corbo::ShootingGridBase::_intermediate_x_constraints
bool _intermediate_x_constraints
Definition: shooting_grid_base.h:215
corbo::DiscretizationGridInterface::_u_prev
VectorVertex _u_prev
Definition: discretization_grid_interface.h:190


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