multiple_shooting_edges.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_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_EDGES_MULTIPLE_SHOOTING_EDGES_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_EDGES_MULTIPLE_SHOOTING_EDGES_H_
27 
29 
35 
36 #include <functional>
37 #include <memory>
38 
39 namespace corbo {
40 
41 // Refer to MSVariableDynamicsOnlyEdge for the variable dt case.
42 // we could always use the variabledt edge, since dt is fixed in that case.
43 // However, we need some benchmarks how much time it requires to always iterate the fixed vertex.. (probably not much?)
44 class MSDynamicsOnlyEdge : public Edge<VectorVertex, VectorVertex, VectorVertex>
45 {
46  public:
47  using Ptr = std::shared_ptr<MSDynamicsOnlyEdge>;
48  using UPtr = std::unique_ptr<MSDynamicsOnlyEdge>;
49 
50  explicit MSDynamicsOnlyEdge(SystemDynamicsInterface::Ptr dynamics, VectorVertex& x1, VectorVertex& u1, VectorVertex& x2, double dt)
51  : Edge<VectorVertex, VectorVertex, VectorVertex>(x1, u1, x2), _dt(dt), _dynamics(dynamics)
52  {
53  _x1 = static_cast<const VectorVertex*>(_vertices[0]);
54  _u1 = static_cast<const VectorVertex*>(_vertices[1]);
55  _x2 = static_cast<const VectorVertex*>(_vertices[2]);
56  }
57 
58  // implements interface method
59  int getDimension() const override
60  {
61  assert(_dynamics);
62  return _dynamics->getStateDimension();
63  }
64  // implement in child class:
65  bool isLinear() const override { return false; }
66 
67  // bool providesJacobian() const override { return false; }
68 
69  bool isLeastSquaresForm() const override { return false; }
70 
71  void computeValues(Eigen::Ref<Eigen::VectorXd> values) override
72  {
73  assert(_integrator);
74  assert(_dynamics);
75  assert(_x1->getDimension() == _dynamics->getStateDimension());
76  assert(_u1->getDimension() == _dynamics->getInputDimension());
77  assert(_x2->getDimension() == _dynamics->getStateDimension());
78 
79  _integrator->computeEqualityConstraint(_x1->values(), _u1->values(), _x2->values(), _dt, *_dynamics, values);
80  }
81 
83 
84  private:
85  double _dt;
88 
89  const VectorVertex* _x1 = nullptr;
90  const VectorVertex* _u1 = nullptr;
91  const VectorVertex* _x2 = nullptr;
92 
93  public:
95 };
96 
97 class MSVariableDynamicsOnlyEdge : public Edge<VectorVertex, VectorVertex, VectorVertex, ScalarVertex>
98 {
99  public:
100  using Ptr = std::shared_ptr<MSVariableDynamicsOnlyEdge>;
101  using UPtr = std::unique_ptr<MSVariableDynamicsOnlyEdge>;
102 
104  : Edge<VectorVertex, VectorVertex, VectorVertex, ScalarVertex>(x1, u1, x2, dt), _dynamics(dynamics)
105  {
106  _x1 = static_cast<const VectorVertex*>(_vertices[0]);
107  _u1 = static_cast<const VectorVertex*>(_vertices[1]);
108  _x2 = static_cast<const VectorVertex*>(_vertices[2]);
109  _dt = static_cast<const ScalarVertex*>(_vertices[3]);
110  }
111 
112  // implements interface method
113  int getDimension() const override
114  {
115  assert(_dynamics);
116  return _dynamics->getStateDimension();
117  }
118  // implement in child class:
119  bool isLinear() const override { return false; }
120 
121  // bool providesJacobian() const override { return false; }
122 
123  bool isLeastSquaresForm() const override { return false; }
124 
126  {
127  assert(_integrator);
128  assert(_dynamics);
129  assert(_x1->getDimension() == _dynamics->getStateDimension());
130  assert(_u1->getDimension() == _dynamics->getInputDimension());
131  assert(_x2->getDimension() == _dynamics->getStateDimension());
132 
133  _integrator->computeEqualityConstraint(_x1->values(), _u1->values(), _x2->values(), _dt->value(), *_dynamics, values);
134  }
135 
136  void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator) { _integrator = integrator; }
137 
138  private:
141 
142  const VectorVertex* _x1 = nullptr;
143  const VectorVertex* _u1 = nullptr;
144  const VectorVertex* _x2 = nullptr;
145  const ScalarVertex* _dt = nullptr;
146 
147  public:
149 };
150 
151 class MultipleShootingEdgeSingleControl : public MixedEdge<VectorVertex, VectorVertex, ScalarVertex, VectorVertex>
152 {
153  public:
154  using Ptr = std::shared_ptr<MultipleShootingEdgeSingleControl>;
155  using UPtr = std::unique_ptr<MultipleShootingEdgeSingleControl>;
156 
159  VectorVertex& x_k, VectorVertex& u_k, ScalarVertex& dt_k, VectorVertex& x_kp1)
160  : MixedEdge<VectorVertex, VectorVertex, ScalarVertex, VectorVertex>(x_k, u_k, dt_k, x_kp1),
161  _stage_cost(stage_cost),
162  _stage_eq(stage_eq),
163  _stage_ineq(stage_ineq),
164  _dynamics(dynamics),
165  _k(k)
166  {
167  assert(_dynamics);
168 
169  _obj_dim = 1; // we have only a single obejtive value
170  _dyn_dim = _dynamics->getStateDimension();
171  _other_eq_dim = _stage_eq ? _stage_eq->getIntegralStateControlTermDimension(_k) : 0;
172  _ineq_dim = _stage_ineq ? _stage_ineq->getIntegralStateControlTermDimension(_k) : 0;
173 
175 
176  // TODO(roesmann) see notes at member declaration;
177  _values.resize(_current.size());
178 
179  _xkvert = static_cast<const VectorVertex*>(_vertices[0]);
180  _ukvert = static_cast<const VectorVertex*>(_vertices[1]);
181  _dtvert = static_cast<const ScalarVertex*>(_vertices[2]);
182  _xnextvert = static_cast<const VectorVertex*>(_vertices[3]);
183 
185  }
186 
187  // implements interface method
188  int getObjectiveDimension() const override { return _obj_dim; }
189  // implements interface method
190  int getEqualityDimension() const override { return _dyn_dim + _other_eq_dim; }
191  // implements interface method
192  int getInequalityDimension() const override { return _ineq_dim; }
193 
194  // implement in child class:
195  // TODO(roesmann) implement if appropriate
196  bool isObjectiveLinear() const override { return false; }
197  bool isEqualityLinear() const override { return false; }
198  bool isInequalityLinear() const override { return false; }
199 
200  // bool providesJacobian() const override { return false; }
201 
202  // TODO(roesmann): integral of squared functions is not always the same as the squared integral of functions
203  bool isObjectiveLeastSquaresForm() const override { return false; }
204 
205  void precompute() override
206  {
207  assert(_integrator);
208  assert(_dynamics);
209 
210  assert(_xkvert->getDimension() == _dynamics->getStateDimension());
211  assert(_ukvert->getDimension() == _dynamics->getInputDimension());
212 
213  // get current values (we must avoid alias, hence we need to copy)
214  if (_obj_dim > 0) _current[0] = 0;
215  _current.segment(_obj_dim, _dyn_dim) = _xkvert->values();
216  int tail = _other_eq_dim + _ineq_dim;
217  if (tail > 0) _current.tail(tail).setZero();
218 
219  // TODO(roesmann) check if we can ensure to avoid alias in the integrator part to speed up simple integrators
220  // first simple tests with replacing _values by _current led to different (wrong) results
221  // _integrator->integrate(_current, _dtvert->value(), _integrand, _values);
223  }
224  void computeObjectiveValues(Eigen::Ref<Eigen::VectorXd> obj_values) override
225  {
226  if (_obj_dim > 0) obj_values[0] = _values[0];
227  }
228  void computeEqualityValues(Eigen::Ref<Eigen::VectorXd> eq_values) override
229  {
230  // system dynamics result must comply with subsequent state
231  assert(_xnextvert->values().size() == _dyn_dim);
232 
233  // _values.segment(_obj_dim, _dyn_dim) -= x_next->values();
234  eq_values.head(_dyn_dim).noalias() = _values.segment(_obj_dim, _dyn_dim) - _xnextvert->values();
235  eq_values.tail(_other_eq_dim) = _values.segment(_obj_dim + _dyn_dim, _other_eq_dim);
236  }
237  void computeInequalityValues(Eigen::Ref<Eigen::VectorXd> ineq_values) override
238  {
239  if (_ineq_dim > 0) ineq_values = _values.tail(_ineq_dim);
240  }
241 
242  void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator) { _integrator = integrator; }
243 
244  protected:
245  void configureIntegrand()
246  {
247  _integrand = [&](const Eigen::VectorXd& current, Eigen::Ref<Eigen::VectorXd> result) {
248  assert(_ukvert);
249  assert(_dtvert);
250 
251  int idx = 0;
252  _dynamics->dynamics(current.segment(_obj_dim, _dyn_dim), _ukvert->values(), result.segment(_obj_dim, _dyn_dim));
253  if (_obj_dim > 0)
254  {
255  assert(_obj_dim == 1);
256  _stage_cost->computeIntegralStateControlTerm(_k, current.segment(_obj_dim, _dyn_dim), _ukvert->values(), result.head(1));
257  idx += 1;
258  }
259  idx += _dyn_dim;
260  if (_other_eq_dim > 0)
261  {
262  _stage_eq->computeIntegralStateControlTerm(_k, current.segment(_obj_dim, _dyn_dim), _ukvert->values(),
263  result.segment(idx, _other_eq_dim));
265  }
266  if (_ineq_dim)
267  {
268  _stage_ineq->computeIntegralStateControlTerm(_k, current.segment(_obj_dim, _dyn_dim), _ukvert->values(),
269  result.segment(idx, _ineq_dim));
270  idx += _ineq_dim;
271  }
272  assert(idx == result.size());
273  };
274  }
275 
276  private:
277  const VectorVertex* _xkvert = nullptr;
278  const VectorVertex* _ukvert = nullptr;
279  const ScalarVertex* _dtvert = nullptr;
280  const VectorVertex* _xnextvert = nullptr;
281 
282  int _dyn_dim = 0;
283  int _obj_dim = 0;
284  int _other_eq_dim = 0;
285  int _ineq_dim = 0;
286 
287  Eigen::VectorXd _current;
288  Eigen::VectorXd _values; // TODO(roesmann): if integrators are alias safe we can remove _values in favor of just _current
289 
290  std::function<void(const Eigen::VectorXd&, Eigen::Ref<Eigen::VectorXd>)> _integrand;
291 
295 
298 
299  int _k = 0;
300 
301  public:
303 };
304 
305 class MultipleShootingEdgeSingleControlTimeScaling : public MixedEdge<VectorVertex, VectorVertex, ScalarVertex, VectorVertex>
306 {
307  public:
308  using Ptr = std::shared_ptr<MultipleShootingEdgeSingleControlTimeScaling>;
309  using UPtr = std::unique_ptr<MultipleShootingEdgeSingleControlTimeScaling>;
310 
313  int k, VectorVertex& x_k, VectorVertex& u_k, ScalarVertex& time, VectorVertex& x_kp1,
314  double dt)
316  _stage_cost(stage_cost),
317  _stage_eq(stage_eq),
318  _stage_ineq(stage_ineq),
319  _dynamics(dynamics),
320  _dt(dt),
321  _k(k)
322  {
323  assert(_dynamics);
324 
325  _obj_dim = 1; // we have only a single obejtive value
326  _dyn_dim = _dynamics->getStateDimension();
327  _other_eq_dim = _stage_eq ? _stage_eq->getIntegralStateControlTermDimension(_k) : 0;
328  _ineq_dim = _stage_ineq ? _stage_ineq->getIntegralStateControlTermDimension(_k) : 0;
329 
331 
332  // TODO(roesmann) see notes at member declaration;
333  _values.resize(_current.size());
334 
335  _xkvert = static_cast<const VectorVertex*>(_vertices[0]);
336  _ukvert = static_cast<const VectorVertex*>(_vertices[1]);
337  _timevert = static_cast<const ScalarVertex*>(_vertices[2]);
338  _xnextvert = static_cast<const VectorVertex*>(_vertices[3]);
339 
341  }
342 
343  // implements interface method
344  int getObjectiveDimension() const override { return _obj_dim; }
345  // implements interface method
346  int getEqualityDimension() const override { return _dyn_dim + _other_eq_dim; }
347  // implements interface method
348  int getInequalityDimension() const override { return _ineq_dim; }
349 
350  // implement in child class:
351  // TODO(roesmann) implement if appropriate
352  bool isObjectiveLinear() const override { return false; }
353  bool isEqualityLinear() const override { return false; }
354  bool isInequalityLinear() const override { return false; }
355 
356  // bool providesJacobian() const override { return false; }
357 
358  // TODO(roesmann): integral of squared functions is not always the same as the squared integral of functions
359  bool isObjectiveLeastSquaresForm() const override { return false; }
360 
361  void precompute() override
362  {
363  assert(_integrator);
364  assert(_dynamics);
365 
366  assert(_xkvert->getDimension() == _dynamics->getStateDimension());
367  assert(_ukvert->getDimension() == _dynamics->getInputDimension());
368 
369  // get current values (we must avoid alias, hence we need to copy)
370  if (_obj_dim > 0) _current[0] = 0;
371  _current.segment(_obj_dim, _dyn_dim) = _xkvert->values();
372  int tail = _other_eq_dim + _ineq_dim;
373  if (tail > 0) _current.tail(tail).setZero();
374 
375  // TODO(roesmann) check if we can ensure to avoid alias in the integrator part to speed up simple integrators
376  // first simple tests with replacing _values by _current led to different (wrong) results
377  // _integrator->integrate(_current, _dtvert->value(), _integrand, _values);
378  _integrator->solveIVP(_current, _dt, _integrand, _values);
379  }
380  void computeObjectiveValues(Eigen::Ref<Eigen::VectorXd> obj_values) override
381  {
382  if (_obj_dim > 0) obj_values[0] = _values[0];
383  }
384  void computeEqualityValues(Eigen::Ref<Eigen::VectorXd> eq_values) override
385  {
386  // system dynamics result must comply with subsequent state
387  assert(_xnextvert->values().size() == _dyn_dim);
388 
389  // _values.segment(_obj_dim, _dyn_dim) -= x_next->values();
390  eq_values.head(_dyn_dim).noalias() = _values.segment(_obj_dim, _dyn_dim) - _xnextvert->values();
391  eq_values.tail(_other_eq_dim) = _values.segment(_obj_dim + _dyn_dim, _other_eq_dim);
392  }
393  void computeInequalityValues(Eigen::Ref<Eigen::VectorXd> ineq_values) override
394  {
395  if (_ineq_dim > 0) ineq_values = _values.tail(_ineq_dim);
396  }
397 
398  void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator) { _integrator = integrator; }
399 
400  protected:
401  void configureIntegrand()
402  {
403  _integrand = [&](const Eigen::VectorXd& current, Eigen::Ref<Eigen::VectorXd> result) {
404  assert(_ukvert);
405  assert(_timevert);
406 
407  int idx = 0;
408  _dynamics->dynamics(current.segment(_obj_dim, _dyn_dim), _ukvert->values(), result.segment(_obj_dim, _dyn_dim));
409  // time scaling:
410  result.segment(_obj_dim, _dyn_dim) *= _timevert->value();
411 
412  if (_obj_dim > 0)
413  {
414  assert(_obj_dim == 1);
415  _stage_cost->computeIntegralStateControlTerm(_k, current.segment(_obj_dim, _dyn_dim), _ukvert->values(), result.head(1));
416  idx += 1;
417  }
418  idx += _dyn_dim;
419  if (_other_eq_dim > 0)
420  {
421  _stage_eq->computeIntegralStateControlTerm(_k, current.segment(_obj_dim, _dyn_dim), _ukvert->values(),
422  result.segment(idx, _other_eq_dim));
424  }
425  if (_ineq_dim)
426  {
427  _stage_ineq->computeIntegralStateControlTerm(_k, current.segment(_obj_dim, _dyn_dim), _ukvert->values(),
428  result.segment(idx, _ineq_dim));
429  idx += _ineq_dim;
430  }
431  assert(idx == result.size());
432  };
433  }
434 
435  private:
436  const VectorVertex* _xkvert = nullptr;
437  const VectorVertex* _ukvert = nullptr;
438  const ScalarVertex* _timevert = nullptr;
439  const VectorVertex* _xnextvert = nullptr;
440 
441  int _dyn_dim = 0;
442  int _obj_dim = 0;
443  int _other_eq_dim = 0;
444  int _ineq_dim = 0;
445 
446  Eigen::VectorXd _current;
447  Eigen::VectorXd _values; // TODO(roesmann): if integrators are alias safe we can remove _values in favor of just _current
448 
449  std::function<void(const Eigen::VectorXd&, Eigen::Ref<Eigen::VectorXd>)> _integrand;
450 
454 
457 
458  double _dt = 0.1;
459 
460  int _k = 0;
461 
462  public:
464 };
465 
466 // vertex order:
467 // vertex: sk
468 // vertex: sk+1
469 // vertex: u[0]
470 // vertex: u[1]
471 // vertex: u[...]
472 // vertex: u[nc-1]
473 // vertex: dt[0]
474 // vertex: dt[1]
475 // vertex: dt[...]
476 // vertex: dt[nt-1]
478 {
479  public:
480  using Ptr = std::shared_ptr<MultipleShootingEdge>;
481  using UPtr = std::unique_ptr<MultipleShootingEdge>;
482 
484  StageInequalityConstraint::ConstPtr stage_ineq, int k, int n_interval, int nc_interval, int nt_interval,
485  bool eval_intermediate_constr)
486  : MixedEdge<>(2 + nc_interval + nt_interval),
487  _stage_cost(stage_cost),
488  _stage_eq(stage_eq),
489  _stage_ineq(stage_ineq),
490  _n_interval(n_interval),
491  _nc_interval(nc_interval),
492  _nt_interval(nt_interval),
493  _eval_intermediate_constr(eval_intermediate_constr),
494  _dynamics(dynamics),
495  _k(k)
496  {
497  }
498 
499  void finalize()
500  {
501  assert(_dynamics);
502  assert((int)_vertices.size() == 2 + _nc_interval + _nt_interval);
503 
504  _shooting_node = static_cast<const VectorVertex*>(_vertices[0]);
505 
506  _int_obj_dim = (_stage_cost && _stage_cost->getIntegralStateControlTermDimension(_k) > 0) ? 1 : 0; // we have only a single obejtive value
507  _dyn_dim = _dynamics->getStateDimension();
508 
509  _other_int_eq_dim = _stage_eq ? _stage_eq->getIntegralStateControlTermDimension(_k) : 0;
510  _int_ineq_dim = _stage_ineq ? _stage_ineq->getIntegralStateControlTermDimension(_k) : 0;
511 
513 
514  // TODO(roesmann) see notes at member declaration;
515  _values.resize(_current.size());
516 
517  // chache total inequality dimension
521 
523 
525  }
526 
527  // implements interface method
528  int getObjectiveDimension() const override { return _total_dim_obj; }
529  // implements interface method
530  int getEqualityDimension() const override { return _total_dim_eq; }
531  // implements interface method
532  int getInequalityDimension() const override { return _total_dim_ineq; }
533 
534  // implement in child class:
535  bool isObjectiveLinear() const override { return false; }
536  bool isEqualityLinear() const override { return false; }
537  bool isInequalityLinear() const override { return false; }
538 
539  // bool providesJacobian() const override { return false; }
540 
541  // TODO(roesmann): integral of squared functions is not always the same as the squared integral of functions
542  bool isObjectiveLeastSquaresForm() const override { return false; }
543 
544  void precompute() override
545  {
546  assert(_integrator);
547  assert(_dynamics);
548  assert((int)_vertices.size() == 2 + _nc_interval + _nt_interval);
549 
550  assert(_shooting_node->getDimension() == _dynamics->getStateDimension());
551 
552  // get current values (we must avoid alias, hence we need to copy)
553  if (_int_obj_dim > 0) _current[0] = 0;
556  if (tail > 0) _current.tail(tail).setZero();
557 
560  {
563 
564  assert(_ukvert->getDimension() == _dynamics->getInputDimension());
565 
566  // compute integral stuff
567  // _integrator->integrate(_current, _dtvert->value(), _integrand, _values);
569 
570  // TODO(roesmann) check if we can ensure to avoid alias in the integrator part to speed up simple integrators
571  // first simple tests with replacing _values by _current led to different (wrong) results
572  if (_current_idx < _n_interval - 2)
573  {
574  _current = _values;
575 
576  // also compute intermediate state dependend stuff
578  {
579  const int k = _k + _current_idx;
581 
582  if (_nonint_obj_dim > 0)
583  {
585  _stage_cost->computeConcatenatedNonIntegralStateTerms(k, xk, _ukvert->values(), _dtvert->value(), cost_segment, true);
586  }
587 
588  if (_nonint_eq_dim > 0)
589  {
591  _stage_eq->computeConcatenatedNonIntegralStateTerms(k, xk, _ukvert->values(), _dtvert->value(), eq_segment, false);
592  }
593 
594  if (_nonint_ineq_dim > 0)
595  {
597  _stage_ineq->computeConcatenatedNonIntegralStateTerms(k, xk, _ukvert->values(), _dtvert->value(), ineq_segment, false);
598  }
599 
600  // lower bounds
601  if (_dim_lb_x > 0)
602  {
603  int lb_idx = 0;
604  for (int j = 0; j < _shooting_node->getDimension(); ++j)
605  {
607  {
608  _lb_ineq_values(_current_idx * _dim_lb_x + lb_idx) = _shooting_node->lowerBound()[j] - xk[j]; // x_min - x <= 0
609  ++lb_idx;
610  }
611  }
612  }
613 
614  // upper bounds
615  if (_dim_ub_x > 0)
616  {
617  int ub_idx = 0;
618  for (int j = 0; j < _shooting_node->getDimension(); ++j)
619  {
621  {
622  _ub_ineq_values(_current_idx * _dim_ub_x + ub_idx) = xk[j] - _shooting_node->upperBound()[j]; // x - x_max <= 0
623  ++ub_idx;
624  }
625  }
626  }
627  }
628  }
629  }
630  }
631 
632  void computeObjectiveValues(Eigen::Ref<Eigen::VectorXd> obj_values) override
633  {
634  if (_int_obj_dim > 0 && _nonint_obj_dim > 0)
635  {
636  obj_values[0] = _values[0] + _nonint_obj_values.sum();
637  }
638  else if (_int_obj_dim > 0)
639  {
640  obj_values[0] = _values[0];
641  }
642  else if (_nonint_obj_dim > 0)
643  {
644  obj_values[0] = _nonint_obj_values.sum();
645  }
646  }
647  void computeEqualityValues(Eigen::Ref<Eigen::VectorXd> eq_values) override
648  {
649  // system dynamics result must comply with subsequent state
650  const VectorVertex* x_next = static_cast<const VectorVertex*>(_vertices[1]);
651  assert(x_next->values().size() == _dyn_dim);
652 
653  eq_values.head(_dyn_dim).noalias() = _values.segment(_int_obj_dim, _dyn_dim) - x_next->values();
654 
656 
658  {
659  assert(_num_intermediate_states > 0);
661  }
662 
663  assert(eq_values.size() == _dyn_dim + _other_int_eq_dim + _num_intermediate_states * _nonint_eq_dim);
664  }
665  void computeInequalityValues(Eigen::Ref<Eigen::VectorXd> ineq_values) override
666  {
667  if (_int_ineq_dim > 0) ineq_values.head(_int_ineq_dim) = _values.tail(_int_ineq_dim);
668 
670  {
671  assert(_num_intermediate_states > 0);
672  int idx = _int_ineq_dim;
673  if (_nonint_ineq_dim > 0)
674  {
675  ineq_values.segment(idx, _num_intermediate_states * _nonint_ineq_dim) = _nonint_ineq_values;
677  }
678 
679  // bounds
680  if (_dim_lb_x > 0)
681  {
682  ineq_values.segment(idx, _num_intermediate_states * _dim_lb_x) = _lb_ineq_values;
683  // idx += _num_intermediate_states * _nonint_ineq_dim;
684  }
685  if (_dim_ub_x > 0)
686  {
688  // idx += _num_intermediate_states * _nonint_ineq_dim;
689  }
690  }
691 
692  assert(ineq_values.size() == _int_ineq_dim + _num_intermediate_states * (_nonint_ineq_dim + _dim_lb_x + _dim_ub_x));
693  }
694 
695  void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator) { _integrator = integrator; }
696 
697  protected:
699  {
700  if (!_eval_intermediate_constr) return;
701  _num_intermediate_states = _n_interval - 2; // no start and state
702  if (_num_intermediate_states < 1)
703  {
705  return;
706  }
707 
708  // TODO(roesmann): we assume for now that all terms have the same dimension _k!!!
709  _nonint_obj_dim = _stage_cost ? _stage_cost->getConcatenatedNonIntegralStateTermDimension(_k, true) : 0;
710  _nonint_eq_dim = _stage_eq ? _stage_eq->getConcatenatedNonIntegralStateTermDimension(_k, false) : 0;
711  _nonint_ineq_dim = _stage_ineq ? _stage_ineq->getConcatenatedNonIntegralStateTermDimension(_k, false) : 0;
712 
713  // consider number of finite bounds for all vertices
714  // we apply the bounds of vertex x1
715  const VectorVertex* x1 = static_cast<const VectorVertex*>(_vertices[0]);
716  _dim_lb_x = x1->getNumberFiniteLowerBounds(false);
717  _dim_ub_x = x1->getNumberFiniteUpperBounds(false);
718 
719  // update overall dimensions
723 
724  // allocate caches
730  }
731 
732  void configureIntegrand()
733  {
734  _integrand = [&](const Eigen::VectorXd& current, Eigen::Ref<Eigen::VectorXd> result) {
735  assert(_ukvert);
736  assert(_dtvert);
737 
738  const int k_integrand = _k + _current_idx;
739 
740  int idx = 0;
741  _dynamics->dynamics(current.segment(_int_obj_dim, _dyn_dim), _ukvert->values(), result.segment(_int_obj_dim, _dyn_dim));
742  if (_int_obj_dim > 0)
743  {
744  assert(_int_obj_dim == 1);
745  _stage_cost->computeIntegralStateControlTerm(k_integrand, current.segment(_int_obj_dim, _dyn_dim), _ukvert->values(), result.head(1));
746  idx += 1;
747  }
748  idx += _dyn_dim;
749  if (_other_int_eq_dim > 0)
750  {
751  _stage_eq->computeIntegralStateControlTerm(k_integrand, current.segment(_int_obj_dim, _dyn_dim), _ukvert->values(),
752  result.segment(idx, _other_int_eq_dim));
753  idx += _other_int_eq_dim;
754  }
755  if (_int_ineq_dim)
756  {
757  _stage_ineq->computeIntegralStateControlTerm(k_integrand, current.segment(_int_obj_dim, _dyn_dim), _ukvert->values(),
758  result.segment(idx, _int_ineq_dim));
759  idx += _int_ineq_dim;
760  }
761  assert(idx == result.size());
762  };
763  }
764 
765  private:
766  const VectorVertex* _shooting_node = nullptr;
767  VectorVertex* _ukvert = nullptr;
768  ScalarVertex* _dtvert = nullptr;
769 
770  int _dyn_dim = 0;
771 
772  int _int_obj_dim = 0;
773  int _other_int_eq_dim = 0;
774  int _int_ineq_dim = 0;
775 
776  int _nonint_obj_dim = 0;
777  int _nonint_eq_dim = 0;
778  int _nonint_ineq_dim = 0;
779 
780  int _dim_lb_x = 0;
781  int _dim_ub_x = 0;
782 
783  int _total_dim_obj = 0;
784  int _total_dim_eq = 0;
785  int _total_dim_ineq = 0;
786 
787  int _n_interval = 0;
788  int _nc_interval = 0;
789  int _nt_interval = 0;
791  int _current_idx = 0;
792 
793  bool _eval_intermediate_constr = false;
794 
795  Eigen::VectorXd _current;
796  Eigen::VectorXd _values; // TODO(roesmann): if integrators are alias safe we can remove _values in favor of just _current
797 
798  Eigen::VectorXd _nonint_obj_values;
799  Eigen::VectorXd _nonint_ineq_values;
800  Eigen::VectorXd _nonint_eq_values;
801  Eigen::VectorXd _lb_ineq_values;
802  Eigen::VectorXd _ub_ineq_values;
803 
804  std::function<void(const Eigen::VectorXd&, Eigen::Ref<Eigen::VectorXd>)> _integrand;
805 
809 
812 
813  int _k = 0;
814 
815  public:
817 };
818 
819 class MSDynamicsOnlyMultiControlsEdge : public Edge<>
820 {
821  public:
822  using Ptr = std::shared_ptr<MSDynamicsOnlyMultiControlsEdge>;
823  using UPtr = std::unique_ptr<MSDynamicsOnlyMultiControlsEdge>;
824 
825  explicit MSDynamicsOnlyMultiControlsEdge(SystemDynamicsInterface::Ptr dynamics, int num_controls) : Edge<>(3 + num_controls), _dynamics(dynamics)
826  {
827  }
828 
829  void finalize()
830  {
831  _x1 = static_cast<const VectorVertex*>(_vertices[0]);
832  _x2 = static_cast<const VectorVertex*>(_vertices[1]);
833  _dt = static_cast<const ScalarVertex*>(_vertices[2]);
834 
835  _f.resize(_dynamics->getStateDimension());
836  }
837 
838  // implements interface method
839  int getDimension() const override
840  {
841  assert(_dynamics);
842  return _dynamics->getStateDimension();
843  }
844  // implement in child class:
845  bool isLinear() const override { return false; }
846 
847  // bool providesJacobian() const override { return false; }
848 
849  bool isLeastSquaresForm() const override { return false; }
850 
852  {
853  assert(_integrator);
854  assert(_dynamics);
855  assert(_x1->getDimension() == _dynamics->getStateDimension());
856  assert(_x2->getDimension() == _dynamics->getStateDimension());
857  assert(_vertices.size() > 4);
858 
859  const VectorVertex* u = static_cast<const VectorVertex*>(_vertices[3]);
860  _integrator->solveIVP(_x1->values(), u->values(), _dt->value(), *_dynamics, _f);
861 
862  for (int i = 4; i < (int)_vertices.size(); ++i)
863  {
864  u = static_cast<const VectorVertex*>(_vertices[i]);
865  _integrator->solveIVP(_f, u->values(), _dt->value(), *_dynamics, values);
866  _f = values; // TODO(roesmann): avoid this by checking the indices maybe?!
867  }
868  values -= _x2->values();
869  }
870 
872 
873  private:
876 
877  Eigen::VectorXd _f;
878 
879  const VectorVertex* _x1 = nullptr;
880  const VectorVertex* _x2 = nullptr;
881  const ScalarVertex* _dt = nullptr;
882 
883  public:
885 };
886 
888 {
889  public:
890  using Ptr = std::shared_ptr<MSDynamicsOnlyMultiControlsMultiDtsEdge>;
891  using UPtr = std::unique_ptr<MSDynamicsOnlyMultiControlsMultiDtsEdge>;
892 
894  : Edge<>(2 + 2 * num_controls), _dynamics(dynamics)
895  {
896  setVertex(0, x1);
897  setVertex(1, x2);
898  _x1 = static_cast<const VectorVertex*>(_vertices[0]);
899  _x2 = static_cast<const VectorVertex*>(_vertices[1]);
900 
901  _f.resize(dynamics->getStateDimension());
902  }
903 
904  void finalize() {}
905 
906  // implements interface method
907  int getDimension() const override
908  {
909  assert(_dynamics);
910  return _dynamics->getStateDimension();
911  }
912  // implement in child class:
913  bool isLinear() const override { return false; }
914 
915  // bool providesJacobian() const override { return false; }
916 
917  bool isLeastSquaresForm() const override { return false; }
918 
919  void computeValues(Eigen::Ref<Eigen::VectorXd> values) override
920  {
921  assert(_integrator);
922  assert(_dynamics);
923  assert(_x1->getDimension() == _dynamics->getStateDimension());
924  assert(_x2->getDimension() == _dynamics->getStateDimension());
925  assert(_vertices.size() > 5);
926 
927  const VectorVertex* u = static_cast<const VectorVertex*>(_vertices[2]);
928  const ScalarVertex* dt = static_cast<const ScalarVertex*>(_vertices[3]);
929  _integrator->solveIVP(_x1->values(), u->values(), dt->value(), *_dynamics, values);
930 
931  for (int i = 4; i < (int)_vertices.size() - 2; i = i + 2)
932  {
933  u = static_cast<const VectorVertex*>(_vertices[i]);
934  dt = static_cast<const ScalarVertex*>(_vertices[i + 1]);
935  _integrator->solveIVP(values, u->values(), dt->value(), *_dynamics, _f);
936  }
937  u = static_cast<const VectorVertex*>(_vertices[(int)_vertices.size() - 2]);
938  dt = static_cast<const ScalarVertex*>(_vertices.back());
939  _integrator->solveIVP(_f, u->values(), dt->value(), *_dynamics, values);
940  values -= _x2->values();
941  }
942 
943  void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator) { _integrator = integrator; }
944 
945  private:
948 
949  Eigen::VectorXd _f;
950 
951  const VectorVertex* _x1 = nullptr;
952  const VectorVertex* _x2 = nullptr;
953 
954  public:
956 };
957 
958 } // namespace corbo
959 
960 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_EDGES_MULTIPLE_SHOOTING_EDGES_H_
corbo::MultipleShootingEdgeSingleControl::_dyn_dim
int _dyn_dim
Definition: multiple_shooting_edges.h:304
corbo::MultipleShootingEdgeSingleControlTimeScaling::_integrand
std::function< void(const Eigen::VectorXd &, Eigen::Ref< Eigen::VectorXd >)> _integrand
Definition: multiple_shooting_edges.h:471
corbo::MultipleShootingEdgeSingleControlTimeScaling::_stage_ineq
StageInequalityConstraint::ConstPtr _stage_ineq
Definition: multiple_shooting_edges.h:475
corbo::MultipleShootingEdge::_nonint_ineq_values
Eigen::VectorXd _nonint_ineq_values
Definition: multiple_shooting_edges.h:821
corbo::MultipleShootingEdgeSingleControl::MultipleShootingEdgeSingleControl
MultipleShootingEdgeSingleControl(SystemDynamicsInterface::Ptr dynamics, StageCost::ConstPtr stage_cost, StageEqualityConstraint::ConstPtr stage_eq, StageInequalityConstraint::ConstPtr stage_ineq, int k, VectorVertex &x_k, VectorVertex &u_k, ScalarVertex &dt_k, VectorVertex &x_kp1)
Definition: multiple_shooting_edges.h:179
corbo::MSVariableDynamicsOnlyEdge::MSVariableDynamicsOnlyEdge
MSVariableDynamicsOnlyEdge(SystemDynamicsInterface::Ptr dynamics, VectorVertex &x1, VectorVertex &u1, VectorVertex &x2, ScalarVertex &dt)
Definition: multiple_shooting_edges.h:125
corbo::MultipleShootingEdgeSingleControl::computeEqualityValues
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
Definition: multiple_shooting_edges.h:250
corbo::MultipleShootingEdgeSingleControlTimeScaling::isObjectiveLeastSquaresForm
bool isObjectiveLeastSquaresForm() const override
Definition: multiple_shooting_edges.h:381
corbo::VectorVertex::getDimension
int getDimension() const override
Return number of elements/values/components stored in this vertex.
Definition: vector_vertex.h:140
corbo::MultipleShootingEdgeSingleControl::_stage_ineq
StageInequalityConstraint::ConstPtr _stage_ineq
Definition: multiple_shooting_edges.h:316
system_dynamics_interface.h
corbo::MultipleShootingEdgeSingleControlTimeScaling::_xnextvert
const VectorVertex * _xnextvert
Definition: multiple_shooting_edges.h:461
corbo::MultipleShootingEdge::_nonint_obj_values
Eigen::VectorXd _nonint_obj_values
Definition: multiple_shooting_edges.h:820
corbo::MultipleShootingEdge::_nc_interval
int _nc_interval
Definition: multiple_shooting_edges.h:810
corbo::MultipleShootingEdgeSingleControlTimeScaling::getEqualityDimension
int getEqualityDimension() const override
Definition: multiple_shooting_edges.h:368
corbo::MultipleShootingEdge::computeEqualityValues
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
Definition: multiple_shooting_edges.h:669
corbo::MSDynamicsOnlyMultiControlsEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: multiple_shooting_edges.h:873
integrator_interface.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::MultipleShootingEdge::isInequalityLinear
bool isInequalityLinear() const override
Definition: multiple_shooting_edges.h:559
corbo::NumericalIntegratorExplicitInterface::Ptr
std::shared_ptr< NumericalIntegratorExplicitInterface > Ptr
Definition: integrator_interface.h:205
corbo::MSDynamicsOnlyEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: multiple_shooting_edges.h:115
corbo::MultipleShootingEdgeSingleControlTimeScaling::_other_eq_dim
int _other_eq_dim
Definition: multiple_shooting_edges.h:465
corbo::MSDynamicsOnlyMultiControlsEdge::_f
Eigen::VectorXd _f
Definition: multiple_shooting_edges.h:899
corbo::VectorVertex::upperBound
const Eigen::VectorXd & upperBound() const
Read-access to the underlying upper bound vector.
Definition: vector_vertex.h:291
corbo::MultipleShootingEdgeSingleControlTimeScaling::computeInequalityValues
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
Definition: multiple_shooting_edges.h:415
corbo::Edge< VectorVertex, VectorVertex, VectorVertex >::Edge
Edge()=delete
corbo::MSVariableDynamicsOnlyEdge::_x2
const VectorVertex * _x2
Definition: multiple_shooting_edges.h:166
corbo::MultipleShootingEdgeSingleControlTimeScaling::configureIntegrand
void configureIntegrand()
Definition: multiple_shooting_edges.h:423
corbo::MSDynamicsOnlyEdge::_u1
const VectorVertex * _u1
Definition: multiple_shooting_edges.h:134
corbo::MultipleShootingEdge::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: multiple_shooting_edges.h:833
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::finalize
void finalize()
Definition: multiple_shooting_edges.h:926
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge
Definition: multiple_shooting_edges.h:909
corbo::MultipleShootingEdgeSingleControlTimeScaling::isInequalityLinear
bool isInequalityLinear() const override
Definition: multiple_shooting_edges.h:376
corbo::MultipleShootingEdge::computeInequalityValues
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
Definition: multiple_shooting_edges.h:687
corbo::MultipleShootingEdgeSingleControlTimeScaling::isEqualityLinear
bool isEqualityLinear() const override
Definition: multiple_shooting_edges.h:375
corbo::VectorVertex::hasFiniteUpperBound
bool hasFiniteUpperBound(int idx) const override
Check if finite upper bound for a single component is provided.
Definition: vector_vertex.h:224
corbo::MSVariableDynamicsOnlyEdge::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: multiple_shooting_edges.h:161
corbo::Edge<>::setVertex
void setVertex(int idx, VertexInterface &vertex)
Definition: edge.h:261
corbo::MultipleShootingEdgeSingleControl::_stage_eq
StageEqualityConstraint::ConstPtr _stage_eq
Definition: multiple_shooting_edges.h:315
corbo::MSDynamicsOnlyMultiControlsEdge
Definition: multiple_shooting_edges.h:841
corbo::MultipleShootingEdge::getEqualityDimension
int getEqualityDimension() const override
Definition: multiple_shooting_edges.h:552
corbo::MultipleShootingEdgeSingleControl::setIntegrator
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: multiple_shooting_edges.h:264
corbo::MSVariableDynamicsOnlyEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: multiple_shooting_edges.h:147
corbo::MSDynamicsOnlyEdge::UPtr
std::unique_ptr< MSDynamicsOnlyEdge > UPtr
Definition: multiple_shooting_edges.h:92
scalar_vertex.h
corbo::MSVariableDynamicsOnlyEdge::Ptr
std::shared_ptr< MSVariableDynamicsOnlyEdge > Ptr
Definition: multiple_shooting_edges.h:122
corbo::VectorVertex::hasFiniteLowerBound
bool hasFiniteLowerBound(int idx) const override
Check if finite lower bound for a single component is provided.
Definition: vector_vertex.h:218
corbo::MultipleShootingEdgeSingleControlTimeScaling::_ineq_dim
int _ineq_dim
Definition: multiple_shooting_edges.h:466
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: multiple_shooting_edges.h:968
corbo::Edge<>::_vertices
VertexContainer _vertices
Vertex container.
Definition: edge.h:303
corbo::MSDynamicsOnlyEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: multiple_shooting_edges.h:103
corbo::MultipleShootingEdge::_int_ineq_dim
int _int_ineq_dim
Definition: multiple_shooting_edges.h:796
corbo::MultipleShootingEdgeSingleControlTimeScaling::_ukvert
const VectorVertex * _ukvert
Definition: multiple_shooting_edges.h:459
corbo::MSDynamicsOnlyEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: multiple_shooting_edges.h:109
corbo::MultipleShootingEdge
Definition: multiple_shooting_edges.h:499
vector_vertex.h
corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex >::_vertices
const VertexContainer _vertices
Vertex container.
Definition: edge.h:383
corbo::MultipleShootingEdgeSingleControlTimeScaling::_dt
double _dt
Definition: multiple_shooting_edges.h:480
corbo::MultipleShootingEdgeSingleControlTimeScaling::_xkvert
const VectorVertex * _xkvert
Definition: multiple_shooting_edges.h:458
corbo::MultipleShootingEdge::_k
int _k
Definition: multiple_shooting_edges.h:835
corbo::MultipleShootingEdgeSingleControl::isEqualityLinear
bool isEqualityLinear() const override
Definition: multiple_shooting_edges.h:219
corbo::MSDynamicsOnlyMultiControlsEdge::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: multiple_shooting_edges.h:896
corbo::MultipleShootingEdgeSingleControlTimeScaling::_timevert
const ScalarVertex * _timevert
Definition: multiple_shooting_edges.h:460
corbo::MSDynamicsOnlyMultiControlsEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: multiple_shooting_edges.h:867
corbo::MultipleShootingEdge::_int_obj_dim
int _int_obj_dim
Definition: multiple_shooting_edges.h:794
corbo::MultipleShootingEdge::_nonint_obj_dim
int _nonint_obj_dim
Definition: multiple_shooting_edges.h:798
corbo::VectorVertex::values
const Eigen::VectorXd & values() const
Read-access to the underlying value vector.
Definition: vector_vertex.h:284
corbo::MultipleShootingEdge::configureIntegrand
void configureIntegrand()
Definition: multiple_shooting_edges.h:754
corbo::MultipleShootingEdge::_total_dim_eq
int _total_dim_eq
Definition: multiple_shooting_edges.h:806
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: multiple_shooting_edges.h:941
corbo::StageInequalityConstraint::ConstPtr
std::shared_ptr< const StageInequalityConstraint > ConstPtr
Definition: stage_functions.h:320
corbo::MultipleShootingEdgeSingleControlTimeScaling::MultipleShootingEdgeSingleControlTimeScaling
MultipleShootingEdgeSingleControlTimeScaling(SystemDynamicsInterface::Ptr dynamics, StageCost::ConstPtr stage_cost, StageEqualityConstraint::ConstPtr stage_eq, StageInequalityConstraint::ConstPtr stage_ineq, int k, VectorVertex &x_k, VectorVertex &u_k, ScalarVertex &time, VectorVertex &x_kp1, double dt)
Definition: multiple_shooting_edges.h:333
corbo::MSVariableDynamicsOnlyEdge::_dt
const ScalarVertex * _dt
Definition: multiple_shooting_edges.h:167
corbo::MultipleShootingEdgeSingleControlTimeScaling::UPtr
std::unique_ptr< MultipleShootingEdgeSingleControlTimeScaling > UPtr
Definition: multiple_shooting_edges.h:331
corbo::MSDynamicsOnlyEdge::MSDynamicsOnlyEdge
MSDynamicsOnlyEdge(SystemDynamicsInterface::Ptr dynamics, VectorVertex &x1, VectorVertex &u1, VectorVertex &x2, double dt)
Definition: multiple_shooting_edges.h:94
corbo::MultipleShootingEdge::_ukvert
VectorVertex * _ukvert
Definition: multiple_shooting_edges.h:789
corbo::MultipleShootingEdgeSingleControl::_dtvert
const ScalarVertex * _dtvert
Definition: multiple_shooting_edges.h:301
corbo::MultipleShootingEdge::_shooting_node
const VectorVertex * _shooting_node
Definition: multiple_shooting_edges.h:788
corbo::MultipleShootingEdgeSingleControlTimeScaling::_current
Eigen::VectorXd _current
Definition: multiple_shooting_edges.h:468
corbo::MSDynamicsOnlyMultiControlsEdge::MSDynamicsOnlyMultiControlsEdge
MSDynamicsOnlyMultiControlsEdge(SystemDynamicsInterface::Ptr dynamics, int num_controls)
Definition: multiple_shooting_edges.h:847
corbo::MultipleShootingEdgeSingleControl::_other_eq_dim
int _other_eq_dim
Definition: multiple_shooting_edges.h:306
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: multiple_shooting_edges.h:935
corbo::MultipleShootingEdgeSingleControl::_integrand
std::function< void(const Eigen::VectorXd &, Eigen::Ref< Eigen::VectorXd >)> _integrand
Definition: multiple_shooting_edges.h:312
corbo::MultipleShootingEdge::_dim_ub_x
int _dim_ub_x
Definition: multiple_shooting_edges.h:803
corbo::MultipleShootingEdge::getInequalityDimension
int getInequalityDimension() const override
Definition: multiple_shooting_edges.h:554
corbo::MultipleShootingEdge::MultipleShootingEdge
MultipleShootingEdge(SystemDynamicsInterface::Ptr dynamics, StageCost::ConstPtr stage_cost, StageEqualityConstraint::ConstPtr stage_eq, StageInequalityConstraint::ConstPtr stage_ineq, int k, int n_interval, int nc_interval, int nt_interval, bool eval_intermediate_constr)
Definition: multiple_shooting_edges.h:505
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::_x1
const VectorVertex * _x1
Definition: multiple_shooting_edges.h:973
corbo::MultipleShootingEdge::_other_int_eq_dim
int _other_int_eq_dim
Definition: multiple_shooting_edges.h:795
corbo::MixedEdge
Definition: edge.h:310
corbo::MultipleShootingEdgeSingleControlTimeScaling::_dyn_dim
int _dyn_dim
Definition: multiple_shooting_edges.h:463
corbo::MultipleShootingEdgeSingleControl::_stage_cost
StageCost::ConstPtr _stage_cost
Definition: multiple_shooting_edges.h:314
corbo::MSVariableDynamicsOnlyEdge::setIntegrator
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: multiple_shooting_edges.h:158
corbo::MSDynamicsOnlyMultiControlsEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: multiple_shooting_edges.h:861
corbo::MultipleShootingEdge::_lb_ineq_values
Eigen::VectorXd _lb_ineq_values
Definition: multiple_shooting_edges.h:823
corbo::MSDynamicsOnlyMultiControlsEdge::setIntegrator
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: multiple_shooting_edges.h:893
corbo::MultipleShootingEdgeSingleControlTimeScaling::precompute
void precompute() override
Definition: multiple_shooting_edges.h:383
corbo::MultipleShootingEdge::computeObjectiveValues
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
Definition: multiple_shooting_edges.h:654
corbo::MultipleShootingEdge::_dim_lb_x
int _dim_lb_x
Definition: multiple_shooting_edges.h:802
corbo::MSDynamicsOnlyEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: multiple_shooting_edges.h:113
stage_functions.h
corbo::MultipleShootingEdge::precompute
void precompute() override
Definition: multiple_shooting_edges.h:566
corbo::MultipleShootingEdge::activateIntermediateStateCostAndConstraints
void activateIntermediateStateCostAndConstraints()
Definition: multiple_shooting_edges.h:720
corbo::MultipleShootingEdge::isObjectiveLeastSquaresForm
bool isObjectiveLeastSquaresForm() const override
Definition: multiple_shooting_edges.h:564
corbo::MSVariableDynamicsOnlyEdge::_u1
const VectorVertex * _u1
Definition: multiple_shooting_edges.h:165
corbo::MultipleShootingEdgeSingleControlTimeScaling::getInequalityDimension
int getInequalityDimension() const override
Definition: multiple_shooting_edges.h:370
corbo::MultipleShootingEdge::Ptr
std::shared_ptr< MultipleShootingEdge > Ptr
Definition: multiple_shooting_edges.h:502
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: multiple_shooting_edges.h:939
edge.h
corbo::MultipleShootingEdgeSingleControl::_ineq_dim
int _ineq_dim
Definition: multiple_shooting_edges.h:307
corbo::MSDynamicsOnlyMultiControlsEdge::finalize
void finalize()
Definition: multiple_shooting_edges.h:851
corbo::MultipleShootingEdgeSingleControl::computeObjectiveValues
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
Definition: multiple_shooting_edges.h:246
corbo::MSDynamicsOnlyEdge::_dt
double _dt
Definition: multiple_shooting_edges.h:129
corbo::MultipleShootingEdge::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: multiple_shooting_edges.h:832
corbo::MultipleShootingEdgeSingleControl::UPtr
std::unique_ptr< MultipleShootingEdgeSingleControl > UPtr
Definition: multiple_shooting_edges.h:177
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:690
corbo::MultipleShootingEdge::_nonint_eq_dim
int _nonint_eq_dim
Definition: multiple_shooting_edges.h:799
corbo::MultipleShootingEdge::_ub_ineq_values
Eigen::VectorXd _ub_ineq_values
Definition: multiple_shooting_edges.h:824
corbo::MultipleShootingEdgeSingleControl::_ukvert
const VectorVertex * _ukvert
Definition: multiple_shooting_edges.h:300
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
corbo::MultipleShootingEdgeSingleControlTimeScaling::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: multiple_shooting_edges.h:478
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: multiple_shooting_edges.h:969
corbo::MultipleShootingEdge::_total_dim_ineq
int _total_dim_ineq
Definition: multiple_shooting_edges.h:807
corbo::MultipleShootingEdgeSingleControl::Ptr
std::shared_ptr< MultipleShootingEdgeSingleControl > Ptr
Definition: multiple_shooting_edges.h:176
corbo::MultipleShootingEdgeSingleControl::_obj_dim
int _obj_dim
Definition: multiple_shooting_edges.h:305
corbo::MultipleShootingEdgeSingleControl::isObjectiveLeastSquaresForm
bool isObjectiveLeastSquaresForm() const override
Definition: multiple_shooting_edges.h:225
int
return int(ret)+1
corbo::MultipleShootingEdge::_stage_cost
StageCost::ConstPtr _stage_cost
Definition: multiple_shooting_edges.h:828
corbo::MultipleShootingEdgeSingleControlTimeScaling::_stage_cost
StageCost::ConstPtr _stage_cost
Definition: multiple_shooting_edges.h:473
corbo::MultipleShootingEdgeSingleControl::_xkvert
const VectorVertex * _xkvert
Definition: multiple_shooting_edges.h:299
corbo::MultipleShootingEdgeSingleControl::_xnextvert
const VectorVertex * _xnextvert
Definition: multiple_shooting_edges.h:302
corbo::MultipleShootingEdgeSingleControl::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: multiple_shooting_edges.h:319
corbo::MSVariableDynamicsOnlyEdge
Definition: multiple_shooting_edges.h:119
corbo::MultipleShootingEdgeSingleControlTimeScaling::Ptr
std::shared_ptr< MultipleShootingEdgeSingleControlTimeScaling > Ptr
Definition: multiple_shooting_edges.h:330
corbo::MSDynamicsOnlyMultiControlsEdge::_x2
const VectorVertex * _x2
Definition: multiple_shooting_edges.h:902
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::Ptr
std::shared_ptr< MSDynamicsOnlyMultiControlsMultiDtsEdge > Ptr
Definition: multiple_shooting_edges.h:912
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::UPtr
std::unique_ptr< MSDynamicsOnlyMultiControlsMultiDtsEdge > UPtr
Definition: multiple_shooting_edges.h:913
corbo::MSVariableDynamicsOnlyEdge::UPtr
std::unique_ptr< MSVariableDynamicsOnlyEdge > UPtr
Definition: multiple_shooting_edges.h:123
corbo::MultipleShootingEdgeSingleControlTimeScaling::_k
int _k
Definition: multiple_shooting_edges.h:482
corbo::MSDynamicsOnlyEdge::setIntegrator
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: multiple_shooting_edges.h:126
corbo::MSDynamicsOnlyMultiControlsEdge::_x1
const VectorVertex * _x1
Definition: multiple_shooting_edges.h:901
corbo::MSDynamicsOnlyEdge::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: multiple_shooting_edges.h:131
corbo::MultipleShootingEdge::_dtvert
ScalarVertex * _dtvert
Definition: multiple_shooting_edges.h:790
corbo::MultipleShootingEdge::_current
Eigen::VectorXd _current
Definition: multiple_shooting_edges.h:817
corbo::MultipleShootingEdge::_nonint_eq_values
Eigen::VectorXd _nonint_eq_values
Definition: multiple_shooting_edges.h:822
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::MultipleShootingEdge::_total_dim_obj
int _total_dim_obj
Definition: multiple_shooting_edges.h:805
corbo::MultipleShootingEdgeSingleControl
Definition: multiple_shooting_edges.h:173
corbo::MultipleShootingEdgeSingleControlTimeScaling::setIntegrator
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: multiple_shooting_edges.h:420
corbo::ScalarVertex::value
const double & value() const
Get underlying value.
Definition: scalar_vertex.h:225
corbo::MultipleShootingEdgeSingleControl::precompute
void precompute() override
Definition: multiple_shooting_edges.h:227
corbo::MultipleShootingEdgeSingleControl::_values
Eigen::VectorXd _values
Definition: multiple_shooting_edges.h:310
corbo::MultipleShootingEdge::_nt_interval
int _nt_interval
Definition: multiple_shooting_edges.h:811
corbo::MultipleShootingEdgeSingleControlTimeScaling::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: multiple_shooting_edges.h:477
corbo::MultipleShootingEdge::finalize
void finalize()
Definition: multiple_shooting_edges.h:521
corbo::MixedEdge<>::_vertices
VertexContainer _vertices
Vertex container.
Definition: edge.h:457
tail
EIGEN_DEVICE_FUNC SegmentReturnType tail(Index n)
This is the const version of tail(Index).
Definition: BlockMethods.h:949
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: multiple_shooting_edges.h:929
corbo::MultipleShootingEdgeSingleControlTimeScaling::_stage_eq
StageEqualityConstraint::ConstPtr _stage_eq
Definition: multiple_shooting_edges.h:474
corbo::MultipleShootingEdge::getObjectiveDimension
int getObjectiveDimension() const override
Definition: multiple_shooting_edges.h:550
corbo::MultipleShootingEdgeSingleControl::computeInequalityValues
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
Definition: multiple_shooting_edges.h:259
corbo::MultipleShootingEdgeSingleControl::_current
Eigen::VectorXd _current
Definition: multiple_shooting_edges.h:309
corbo::MSDynamicsOnlyEdge::Ptr
std::shared_ptr< MSDynamicsOnlyEdge > Ptr
Definition: multiple_shooting_edges.h:91
corbo::MultipleShootingEdge::_stage_eq
StageEqualityConstraint::ConstPtr _stage_eq
Definition: multiple_shooting_edges.h:829
corbo::MultipleShootingEdgeSingleControlTimeScaling
Definition: multiple_shooting_edges.h:327
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::MSDynamicsOnlyMultiControlsMultiDtsEdge
MSDynamicsOnlyMultiControlsMultiDtsEdge(SystemDynamicsInterface::Ptr dynamics, VectorVertex &x1, VectorVertex &x2, int num_controls)
Definition: multiple_shooting_edges.h:915
corbo::MultipleShootingEdgeSingleControl::isObjectiveLinear
bool isObjectiveLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: multiple_shooting_edges.h:218
corbo::MSDynamicsOnlyEdge::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: multiple_shooting_edges.h:130
corbo::MSVariableDynamicsOnlyEdge::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: multiple_shooting_edges.h:162
corbo::MultipleShootingEdge::_eval_intermediate_constr
bool _eval_intermediate_constr
Definition: multiple_shooting_edges.h:815
corbo::MultipleShootingEdge::_stage_ineq
StageInequalityConstraint::ConstPtr _stage_ineq
Definition: multiple_shooting_edges.h:830
corbo::MultipleShootingEdgeSingleControl::getEqualityDimension
int getEqualityDimension() const override
Definition: multiple_shooting_edges.h:212
corbo::MultipleShootingEdge::setIntegrator
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: multiple_shooting_edges.h:717
corbo::MSVariableDynamicsOnlyEdge::_x1
const VectorVertex * _x1
Definition: multiple_shooting_edges.h:164
corbo::MultipleShootingEdge::_current_idx
int _current_idx
Definition: multiple_shooting_edges.h:813
corbo::ScalarVertex
Vertex implementation for scalar values.
Definition: scalar_vertex.h:72
corbo::MSDynamicsOnlyEdge::_x2
const VectorVertex * _x2
Definition: multiple_shooting_edges.h:135
corbo::MultipleShootingEdge::isEqualityLinear
bool isEqualityLinear() const override
Definition: multiple_shooting_edges.h:558
corbo::MSDynamicsOnlyMultiControlsEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: multiple_shooting_edges.h:871
corbo::MultipleShootingEdge::_dyn_dim
int _dyn_dim
Definition: multiple_shooting_edges.h:792
corbo::MultipleShootingEdge::_nonint_ineq_dim
int _nonint_ineq_dim
Definition: multiple_shooting_edges.h:800
corbo::MSDynamicsOnlyEdge::_x1
const VectorVertex * _x1
Definition: multiple_shooting_edges.h:133
corbo::MSDynamicsOnlyMultiControlsEdge::_dt
const ScalarVertex * _dt
Definition: multiple_shooting_edges.h:903
corbo::MultipleShootingEdgeSingleControlTimeScaling::computeObjectiveValues
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
Definition: multiple_shooting_edges.h:402
corbo::MSVariableDynamicsOnlyEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: multiple_shooting_edges.h:141
corbo::MSVariableDynamicsOnlyEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: multiple_shooting_edges.h:135
corbo::VectorVertex::lowerBound
const Eigen::VectorXd & lowerBound() const
Read-access to the underlying lower bound vector.
Definition: vector_vertex.h:289
corbo::Edge
Templated base edge class that stores an arbitary number of value.
Definition: edge.h:170
corbo::StageEqualityConstraint::ConstPtr
std::shared_ptr< const StageEqualityConstraint > ConstPtr
Definition: stage_functions.h:302
corbo::MultipleShootingEdgeSingleControlTimeScaling::getObjectiveDimension
int getObjectiveDimension() const override
Definition: multiple_shooting_edges.h:366
corbo::MultipleShootingEdge::_integrand
std::function< void(const Eigen::VectorXd &, Eigen::Ref< Eigen::VectorXd >)> _integrand
Definition: multiple_shooting_edges.h:826
corbo::MultipleShootingEdge::_values
Eigen::VectorXd _values
Definition: multiple_shooting_edges.h:818
corbo::MultipleShootingEdgeSingleControl::configureIntegrand
void configureIntegrand()
Definition: multiple_shooting_edges.h:267
corbo::MultipleShootingEdgeSingleControl::_dynamics
SystemDynamicsInterface::Ptr _dynamics
Definition: multiple_shooting_edges.h:318
corbo::VectorVertex
Vertex implementation that stores an Eigen::VectorXd (dynamic dimension)
Definition: vector_vertex.h:73
corbo::MultipleShootingEdgeSingleControlTimeScaling::_obj_dim
int _obj_dim
Definition: multiple_shooting_edges.h:464
corbo::MultipleShootingEdgeSingleControl::getInequalityDimension
int getInequalityDimension() const override
Definition: multiple_shooting_edges.h:214
corbo::StageCost::ConstPtr
std::shared_ptr< const StageCost > ConstPtr
Definition: stage_functions.h:156
corbo::MultipleShootingEdgeSingleControl::_k
int _k
Definition: multiple_shooting_edges.h:321
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::setIntegrator
void setIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: multiple_shooting_edges.h:965
corbo::MultipleShootingEdgeSingleControl::isInequalityLinear
bool isInequalityLinear() const override
Definition: multiple_shooting_edges.h:220
corbo::MultipleShootingEdge::_n_interval
int _n_interval
Definition: multiple_shooting_edges.h:809
corbo::MSVariableDynamicsOnlyEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: multiple_shooting_edges.h:145
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::_x2
const VectorVertex * _x2
Definition: multiple_shooting_edges.h:974
corbo::MultipleShootingEdgeSingleControl::getObjectiveDimension
int getObjectiveDimension() const override
Definition: multiple_shooting_edges.h:210
corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge::_f
Eigen::VectorXd _f
Definition: multiple_shooting_edges.h:971
corbo::MSDynamicsOnlyMultiControlsEdge::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: multiple_shooting_edges.h:897
corbo::MultipleShootingEdge::isObjectiveLinear
bool isObjectiveLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: multiple_shooting_edges.h:557
corbo::MultipleShootingEdgeSingleControlTimeScaling::isObjectiveLinear
bool isObjectiveLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: multiple_shooting_edges.h:374
corbo::MultipleShootingEdge::UPtr
std::unique_ptr< MultipleShootingEdge > UPtr
Definition: multiple_shooting_edges.h:503
corbo::MultipleShootingEdgeSingleControlTimeScaling::_values
Eigen::VectorXd _values
Definition: multiple_shooting_edges.h:469
corbo::MultipleShootingEdge::_num_intermediate_states
int _num_intermediate_states
Definition: multiple_shooting_edges.h:812
corbo::MultipleShootingEdgeSingleControlTimeScaling::computeEqualityValues
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
Definition: multiple_shooting_edges.h:406
corbo::Edge< VectorVertex, VectorVertex, VectorVertex >::_vertices
const VertexContainer _vertices
Vertex container.
Definition: edge.h:258


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