shooting_grid_base.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_DISCRETIZATION_GRIDS_SHOOTING_GRID_BASE_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_DISCRETIZATION_GRIDS_SHOOTING_GRID_BASE_H_
27 
29 
32 
34 
35 #include <memory>
36 
37 namespace corbo {
38 
39 class ShootingGridBase : public DiscretizationGridInterface
40 {
41  public:
42  using Ptr = std::shared_ptr<ShootingGridBase>;
43  using UPtr = std::unique_ptr<ShootingGridBase>;
44 
45  struct ShootingInterval
46  {
47  VectorVertex s;
48  std::vector<VectorVertex> u_seq;
50  };
51 
52  ShootingGridBase() = default;
53  virtual ~ShootingGridBase() = default;
54 
56  DiscretizationGridInterface::Ptr getInstance() const override = 0;
57 
58  GridUpdateResult update(const Eigen::VectorXd& x0, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, NlpFunctions& nlp_fun,
59  OptimizationEdgeSet& edges, SystemDynamicsInterface::Ptr dynamics, bool new_run, const Time& t,
60  ReferenceTrajectoryInterface* sref = nullptr, const Eigen::VectorXd* prev_u = nullptr, double prev_u_dt = 0,
61  ReferenceTrajectoryInterface* xinit = nullptr, ReferenceTrajectoryInterface* uinit = nullptr) override;
62 
63  double getFirstDt() const override { return getDt(); }
64  double getFinalTime() const override { return double(getN() - 1) * getDt(); }
65 
66  bool hasConstantControls() const override { return true; }
67  bool hasSingleDt() const override { return true; }
68  bool isTimeVariableGrid() const override { return !isDtFixedIntended(); }
69  bool isUniformGrid() const override { return true; }
70  bool providesStateTrajectory() const override { return true; } // TODO(roesmann): clarify
71 
72  bool getFirstControlInput(Eigen::VectorXd& u0) override;
73 
74  void getStateAndControlTimeSeries(TimeSeries::Ptr x_sequence, TimeSeries::Ptr u_sequence, double t_max = CORBO_INF_DBL) const override;
75 
76  void clear() override;
77 
78  bool isEmpty() const override { return _intervals.empty(); }
79  bool isValid() const { return !_intervals.empty() && !_intervals.front().u_seq.empty(); }
80 
81  void setN(int n, bool try_resample = true) override
82  {
83  clear(); // resampling not yet implemented
84  setNRef(n);
85  }
86  void setInitialDt(double dt) override { setDtRef(dt); }
87  double getInitialDt() const override { return getDtRef(); }
88  int getInitialN() const override { return getNRef(); }
89 
90  int getNRef() const { return _n_ref; }
91  int getN() const override;
92  void setNumControlsPerShootingInterval(int num_u_per_interv) { _num_u_per_interv_ref = num_u_per_interv; }
93  void setNumControlsPerShootingInterval(int num_u_per_interv, bool intermediate_x_constraints)
94  {
95  setNumControlsPerShootingInterval(num_u_per_interv);
96  _intermediate_x_constraints = intermediate_x_constraints;
97  }
98  void setNRef(int n);
99  void setDtRef(double dt) { _dt_ref = dt; }
100  double getDtRef() const { return _dt_ref; }
101  double getDt() const { return _dt.value(); }
102  void setWarmStart(bool active) { _warm_start = active; }
103 
105 
107 
109  {
110  _xf_fixed = xf_fixed;
111  setModified(true);
112  }
113 
114  // VertexSet methods
115  std::vector<VertexInterface*>& getActiveVertices() override { return _active_vertices; }
116  void getVertices(std::vector<VertexInterface*>& vertices) override;
117 
118 #ifdef MESSAGE_SUPPORT
119  void fromMessage(const messages::DiscretizationGrid& message, std::stringstream* issues) override {}
120  void toMessage(messages::DiscretizationGrid& message) const override {}
121 #endif
122 
123  protected:
124  void initializeSequences(const Eigen::VectorXd& x0, const Eigen::VectorXd& xf, ReferenceTrajectoryInterface& uref, NlpFunctions& nlp_fun);
125  void initializeSequences(const Eigen::VectorXd& x0, const Eigen::VectorXd& xf, ReferenceTrajectoryInterface& xref,
127  void warmStartShifting(const Eigen::VectorXd& x0);
128 
129  virtual bool adaptGrid(bool new_run, NlpFunctions& nlp_fun) { return false; } // A subclass might add a grid adaptation, returns true if adapted
130 
131  int findNearestShootingInterval(const Eigen::VectorXd& x0);
132 
133  void updateBounds(const NlpFunctions& nlp_fun);
134 
135  void resampleTrajectory(int n_new, NlpFunctions& nlp_fun);
136 
138 
139  virtual void createEdges(NlpFunctions& nlp_fun, OptimizationEdgeSet& edges, SystemDynamicsInterface::Ptr dynamics) = 0;
140 
141  virtual bool isDtFixedIntended() const { return true; }
142  virtual bool isMovingHorizonWarmStartActive() const { return _warm_start; }
143  virtual bool isGridAdaptActive() const { return false; }
144 
145  void computeActiveVertices() override;
146 
147  protected:
148  virtual bool isXfShootingNode() const { return true; }
149 
151 
152  std::vector<ShootingInterval> _intervals;
155  std::vector<VertexInterface*> _active_vertices;
156 
157  int _num_u_per_interv_ref = 1; // 1 -> full discretization
158  int _n_ref = 11;
159  int _n_adapt = 0; // if adaption is on and warmstart of, we might use this n instead of n_ref (only if n_adapt > 0)
160  double _dt_ref = 0.1;
161 
162  bool _warm_start = false;
163  bool _first_run = true;
164 
165  // might be required if the last dt should be fixed or if dt is not fixed
166  Eigen::Matrix<bool, -1, 1> _xf_fixed;
167  double _dt_lb = 0;
168  double _dt_ub = CORBO_INF_DBL;
169 
170  bool _full_discretization = true;
171  bool _intermediate_x_constraints = false;
172 };
173 
174 } // namespace corbo
175 
176 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_DISCRETIZATION_GRIDS_SHOOTING_GRID_BASE_H_
corbo::ShootingGridBase::adaptGrid
virtual bool adaptGrid(bool new_run, NlpFunctions &nlp_fun)
Definition: shooting_grid_base.h:173
corbo::ShootingGridBase::_integrator
NumericalIntegratorExplicitInterface::Ptr _integrator
Definition: shooting_grid_base.h:194
corbo::ShootingGridBase::isEmpty
bool isEmpty() const override
Definition: shooting_grid_base.h:122
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::providesStateTrajectory
bool providesStateTrajectory() const override
Definition: shooting_grid_base.h:114
corbo::ShootingGridBase::_intervals
std::vector< ShootingInterval > _intervals
Definition: shooting_grid_base.h:196
corbo::ShootingGridBase::setWarmStart
void setWarmStart(bool active)
Definition: shooting_grid_base.h:146
corbo::ShootingGridBase::_n_adapt
int _n_adapt
Definition: shooting_grid_base.h:203
corbo::ReferenceTrajectoryInterface
Interface class for reference trajectories.
Definition: reference_trajectory.h:82
corbo::ShootingGridBase::getFirstControlInput
bool getFirstControlInput(Eigen::VectorXd &u0) override
Definition: shooting_grid_base.cpp:415
integrator_interface.h
corbo::ShootingGridBase::_dt_ub
double _dt_ub
Definition: shooting_grid_base.h:212
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::NumericalIntegratorExplicitInterface::Ptr
std::shared_ptr< NumericalIntegratorExplicitInterface > Ptr
Definition: integrator_interface.h:205
corbo::ShootingGridBase::setInitialDt
void setInitialDt(double dt) override
Definition: shooting_grid_base.h:130
corbo::NlpFunctions
Definition: nlp_functions.h:58
corbo::ShootingGridBase::_first_run
bool _first_run
Definition: shooting_grid_base.h:207
corbo::ShootingGridBase::_n_ref
int _n_ref
Definition: shooting_grid_base.h:202
scalar_vertex.h
corbo::ShootingGridBase::clear
void clear() override
Definition: shooting_grid_base.cpp:578
corbo::ShootingGridBase::getVertices
void getVertices(std::vector< VertexInterface * > &vertices) override
Definition: shooting_grid_base.cpp:589
corbo::ShootingGridBase::ShootingGridBase
ShootingGridBase()=default
corbo::ShootingGridBase::warmStartShifting
void warmStartShifting(const Eigen::VectorXd &x0)
Definition: shooting_grid_base.cpp:314
discretization_grid_interface.h
corbo::CORBO_INF_DBL
constexpr const double CORBO_INF_DBL
Representation for infinity (double version)
Definition: core/include/corbo-core/types.h:75
vector_vertex.h
corbo::ShootingGridBase::_dt_ref
double _dt_ref
Definition: shooting_grid_base.h:204
corbo::ShootingGridBase::getFinalTime
double getFinalTime() const override
Definition: shooting_grid_base.h:108
corbo::ShootingGridBase::isGridAdaptActive
virtual bool isGridAdaptActive() const
Definition: shooting_grid_base.h:187
corbo::ShootingGridBase::~ShootingGridBase
virtual ~ShootingGridBase()=default
corbo::ShootingGridBase::hasConstantControls
bool hasConstantControls() const override
Definition: shooting_grid_base.h:110
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::DiscretizationGridInterface::Ptr
std::shared_ptr< DiscretizationGridInterface > Ptr
Definition: discretization_grid_interface.h:107
corbo::ShootingGridBase::_xf_fixed
Eigen::Matrix< bool, -1, 1 > _xf_fixed
Definition: shooting_grid_base.h:210
corbo::ShootingGridBase::isTimeVariableGrid
bool isTimeVariableGrid() const override
Definition: shooting_grid_base.h:112
corbo::ShootingGridBase::getInstance
DiscretizationGridInterface::Ptr getInstance() const override=0
Return a newly created shared instance of the implemented class.
corbo::ShootingGridBase::getActiveVertices
std::vector< VertexInterface * > & getActiveVertices() override
Definition: shooting_grid_base.h:159
corbo::ShootingGridBase::getN
int getN() const override
Definition: shooting_grid_base.cpp:423
corbo::ShootingGridBase::isDtFixedIntended
virtual bool isDtFixedIntended() const
Definition: shooting_grid_base.h:185
corbo::ShootingGridBase::findNearestShootingInterval
int findNearestShootingInterval(const Eigen::VectorXd &x0)
Definition: shooting_grid_base.cpp:378
corbo::ShootingGridBase::computeActiveVertices
void computeActiveVertices() override
Definition: shooting_grid_base.cpp:605
corbo::ShootingGridBase::isUniformGrid
bool isUniformGrid() const override
Definition: shooting_grid_base.h:113
corbo::ShootingGridBase::setConsiderIntermediateStateConstraints
void setConsiderIntermediateStateConstraints(bool active)
Definition: shooting_grid_base.h:148
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:690
corbo::OptimizationEdgeSet
Definition: edge_set.h:96
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
corbo::ShootingGridBase::resampleTrajectory
void resampleTrajectory(int n_new, NlpFunctions &nlp_fun)
Definition: shooting_grid_base.cpp:495
corbo::ShootingGridBase::setXfFixed
void setXfFixed(const Eigen::Matrix< bool, -1, 1 > &xf_fixed)
Definition: shooting_grid_base.h:152
corbo::ShootingGridBase::getDtRef
double getDtRef() const
Definition: shooting_grid_base.h:144
corbo::ShootingGridBase::isMovingHorizonWarmStartActive
virtual bool isMovingHorizonWarmStartActive() const
Definition: shooting_grid_base.h:186
corbo::ShootingGridBase::update
GridUpdateResult update(const Eigen::VectorXd &x0, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics, bool new_run, const Time &t, ReferenceTrajectoryInterface *sref=nullptr, const Eigen::VectorXd *prev_u=nullptr, double prev_u_dt=0, ReferenceTrajectoryInterface *xinit=nullptr, ReferenceTrajectoryInterface *uinit=nullptr) override
Definition: shooting_grid_base.cpp:61
corbo::ShootingGridBase::getFirstDt
double getFirstDt() const override
Definition: shooting_grid_base.h:107
corbo::ScalarVertex::value
const double & value() const
Get underlying value.
Definition: scalar_vertex.h:225
corbo::ShootingGridBase::setNumericalIntegrator
void setNumericalIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
Definition: shooting_grid_base.h:150
corbo::ShootingGridBase::createEdges
virtual void createEdges(NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics)=0
corbo::ShootingGridBase::getStateAndControlTimeSeries
void getStateAndControlTimeSeries(TimeSeries::Ptr x_sequence, TimeSeries::Ptr u_sequence, double t_max=CORBO_INF_DBL) const override
Return state and control trajectory as time series object (shared instance)
Definition: shooting_grid_base.cpp:622
corbo::ScalarVertex
Vertex implementation for scalar values.
Definition: scalar_vertex.h:72
corbo::ShootingGridBase::setNRef
void setNRef(int n)
Definition: shooting_grid_base.cpp:434
corbo::ShootingGridBase::isValid
bool isValid() const
Definition: shooting_grid_base.h:123
corbo::ShootingGridBase::_dt
ScalarVertex _dt
Definition: shooting_grid_base.h:197
corbo::ShootingGridBase::getInitialDt
double getInitialDt() const override
Definition: shooting_grid_base.h:131
Eigen::Matrix< bool, -1, 1 >
corbo::ShootingGridBase::_active_vertices
std::vector< VertexInterface * > _active_vertices
Definition: shooting_grid_base.h:199
corbo::ShootingGridBase::initializeSequences
void initializeSequences(const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun)
Definition: shooting_grid_base.cpp:163
corbo::ShootingGridBase::_dt_lb
double _dt_lb
Definition: shooting_grid_base.h:211
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::ShootingGridBase::getInitialN
int getInitialN() const override
Definition: shooting_grid_base.h:132
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::ShootingGridBase::checkAndInitializeXfFixedFlags
bool checkAndInitializeXfFixedFlags(int dim_x)
Definition: shooting_grid_base.cpp:448
corbo::ShootingGridBase::setNumControlsPerShootingInterval
void setNumControlsPerShootingInterval(int num_u_per_interv)
Definition: shooting_grid_base.h:136
corbo::ShootingGridBase::getDt
double getDt() const
Definition: shooting_grid_base.h:145
corbo::ShootingGridBase::_full_discretization
bool _full_discretization
Definition: shooting_grid_base.h:214
corbo::ShootingGridBase::isXfShootingNode
virtual bool isXfShootingNode() const
Definition: shooting_grid_base.h:192
corbo::ShootingGridBase::ShootingInterval::u_seq
std::vector< VectorVertex > u_seq
Definition: shooting_grid_base.h:92
corbo::VertexSetInterface::setModified
void setModified(bool modified)
Definition: vertex_set.h:126
corbo::ShootingGridBase::getNRef
int getNRef() const
Definition: shooting_grid_base.h:134
corbo::ShootingGridBase::ShootingInterval::s
VectorVertex s
Definition: shooting_grid_base.h:91
corbo::ShootingGridBase::hasSingleDt
bool hasSingleDt() const override
Definition: shooting_grid_base.h:111
corbo::ShootingGridBase::setN
void setN(int n, bool try_resample=true) override
Return dimension of the control input dimension in the grid.
Definition: shooting_grid_base.h:125
corbo::PartiallyFixedVectorVertex
Vector based vertex with support for partially fixed components.
Definition: vector_vertex.h:298
corbo::ShootingGridBase::_intermediate_x_constraints
bool _intermediate_x_constraints
Definition: shooting_grid_base.h:215
corbo::ShootingGridBase::UPtr
std::unique_ptr< ShootingGridBase > UPtr
Definition: shooting_grid_base.h:87
corbo::ShootingGridBase::updateBounds
void updateBounds(const NlpFunctions &nlp_fun)
Definition: shooting_grid_base.cpp:463
corbo::ShootingGridBase::Ptr
std::shared_ptr< ShootingGridBase > Ptr
Definition: shooting_grid_base.h:86


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