discretization_grid_interface.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_DISCRETIZATION_GRID_INTERFACE_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_DISCRETIZATION_GRIDS_DISCRETIZATION_GRID_INTERFACE_H_
27 
30 
33 
35 
37 
38 #include <corbo-core/factory.h>
40 #include <corbo-core/time_series.h>
41 #include <corbo-core/types.h>
42 
43 #ifdef MESSAGE_SUPPORT
44 #include <corbo-communication/messages/optimal_control/discretization_grids.pb.h>
45 #endif
46 
47 #include <memory>
48 #include <utility>
49 
50 namespace corbo {
51 
52 struct GridUpdateResult
53 {
54  bool vertices_updated = false;
55  bool edges_updated = false;
56 
57  bool updated() const { return vertices_updated || edges_updated; }
58 };
59 
82 class DiscretizationGridInterface : public VertexSetInterface
83 {
84  public:
85  using Ptr = std::shared_ptr<DiscretizationGridInterface>;
86  using UPtr = std::unique_ptr<DiscretizationGridInterface>;
87 
88  DiscretizationGridInterface() = default;
89  DiscretizationGridInterface(int state_dim, int control_dim);
90 
92  virtual ~DiscretizationGridInterface() = default;
93 
94  // TODO(roesmann): detailed description here (very important)
95  // nlp_fun->update must be called inside ...
96  virtual GridUpdateResult update(const Eigen::VectorXd& x0, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref,
97  NlpFunctions& nlp_fun, OptimizationEdgeSet& edges, SystemDynamicsInterface::Ptr dynamics, bool new_run,
98  const Time& t, ReferenceTrajectoryInterface* sref = nullptr, const Eigen::VectorXd* prev_u = nullptr,
99  double prev_u_dt = 0, ReferenceTrajectoryInterface* xinit = nullptr,
100  ReferenceTrajectoryInterface* uinit = nullptr) = 0;
101 
103  virtual Ptr getInstance() const = 0;
104 
107 
109  // int getControlInputDimension() const { return _control_dim; }
110  // //! Return dimension of the state dimension in the grid
111  // int getStateDimension() const { return _state_dim; }
112 
113  virtual void setN(int n, bool try_resample = true) = 0;
114  virtual void setInitialDt(double dt) = 0;
115 
116  virtual int getN() const = 0;
117  virtual double getFirstDt() const = 0;
118  virtual double getFinalTime() const = 0;
119  virtual double getInitialDt() const = 0;
120  virtual int getInitialN() const = 0;
121 
122  // TODO(roesmann): check what we really need:
123  virtual bool hasConstantControls() const = 0;
124  virtual bool hasSingleDt() const = 0;
125  virtual bool isTimeVariableGrid() const = 0;
126  virtual bool isUniformGrid() const = 0;
127  virtual bool providesStateTrajectory() const = 0;
128 
129  // TODO(roesmann): see notes in the optimal_control_problem_interface.h
131  virtual void getStateAndControlTimeSeries(TimeSeries::Ptr x_sequence, TimeSeries::Ptr u_sequence, double t_max = CORBO_INF_DBL) const = 0;
132 
133  virtual bool getFirstControlInput(Eigen::VectorXd& u0) = 0;
134 
135  void clear() override = 0;
136 
137  virtual bool isEmpty() const = 0;
138 
139  // void printGrid();
140 
141 #ifdef MESSAGE_SUPPORT
142  virtual void fromMessage(const messages::DiscretizationGrid& message, std::stringstream* issues) {}
143  virtual void toMessage(messages::DiscretizationGrid& message) const {}
144 #endif
145 
146  protected:
147  // VertexSet methods
148  std::vector<VertexInterface*>& getActiveVertices() override = 0;
149  void getVertices(std::vector<VertexInterface*>& vertices) override = 0;
150  // compute active vertices: override in subclass to be more efficient
151  void computeActiveVertices() override = 0;
152 
153  void setPreviousControl(const Eigen::VectorXd& prev_u, double prev_u_dt)
154  {
155  if (!_u_prev.isFixed() || !_u_prev_dt.isFixed()) setModified(true);
156  _u_prev.values() = prev_u;
157  _u_prev.setFixed(true);
158  _u_prev_dt.value() = prev_u_dt;
159  _u_prev_dt.setFixed(true);
160  }
161  void setLastControlRef(const Eigen::VectorXd& last_u_ref)
162  {
163  if (!_u_ref.isFixed()) setModified(true);
164  _u_ref.values() = last_u_ref;
165  _u_ref.setFixed(true);
166  }
167 
168  VectorVertex _u_prev; // TODO(roesmann): how should we handle this?
169  ScalarVertex _u_prev_dt;
170  VectorVertex _u_ref; // for last control deviation if desired
171 };
172 
173 using DiscretizationGridFactory = Factory<DiscretizationGridInterface>;
174 #define FACTORY_REGISTER_DISCRETIZATION_GRID(type) FACTORY_REGISTER_OBJECT(type, DiscretizationGridInterface)
175 
176 } // namespace corbo
177 
178 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_DISCRETIZATION_GRIDS_DISCRETIZATION_GRID_INTERFACE_H_
corbo::DiscretizationGridInterface::_u_ref
VectorVertex _u_ref
Definition: discretization_grid_interface.h:192
corbo::DiscretizationGridInterface::isEmpty
virtual bool isEmpty() const =0
corbo::DiscretizationGridInterface::getInitialN
virtual int getInitialN() const =0
corbo::DiscretizationGridInterface::hasSingleDt
virtual bool hasSingleDt() const =0
corbo::DiscretizationGridInterface::getActiveVertices
std::vector< VertexInterface * > & getActiveVertices() override=0
corbo::DiscretizationGridInterface::setN
virtual void setN(int n, bool try_resample=true)=0
Return dimension of the control input dimension in the grid.
corbo::DiscretizationGridInterface::clear
void clear() override=0
factory.h
corbo::ReferenceTrajectoryInterface
Interface class for reference trajectories.
Definition: reference_trajectory.h:82
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::DiscretizationGridInterface::setPreviousControl
void setPreviousControl(const Eigen::VectorXd &prev_u, double prev_u_dt)
Definition: discretization_grid_interface.h:175
corbo::Factory
Generic factory object.
Definition: factory.h:90
corbo::DiscretizationGridInterface::getInstance
virtual Ptr getInstance() const =0
Return a newly created shared instance of the implemented class.
corbo::DiscretizationGridInterface::getFirstControlInput
virtual bool getFirstControlInput(Eigen::VectorXd &u0)=0
corbo::DiscretizationGridInterface::setLastControlRef
void setLastControlRef(const Eigen::VectorXd &last_u_ref)
Definition: discretization_grid_interface.h:183
corbo::DiscretizationGridInterface::update
virtual 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)=0
corbo::DiscretizationGridInterface::getStateAndControlTimeSeries
virtual void getStateAndControlTimeSeries(TimeSeries::Ptr x_sequence, TimeSeries::Ptr u_sequence, double t_max=CORBO_INF_DBL) const =0
Return state and control trajectory as time series object (shared instance)
corbo::DiscretizationGridInterface::_u_prev_dt
ScalarVertex _u_prev_dt
Definition: discretization_grid_interface.h:191
scalar_vertex.h
corbo::DiscretizationGridInterface::~DiscretizationGridInterface
virtual ~DiscretizationGridInterface()=default
Virtual destructor.
edge_set.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::DiscretizationGridInterface::getVertices
void getVertices(std::vector< VertexInterface * > &vertices) override=0
corbo::VectorVertex::values
const Eigen::VectorXd & values() const
Read-access to the underlying value vector.
Definition: vector_vertex.h:284
corbo::DiscretizationGridInterface::getFirstDt
virtual double getFirstDt() const =0
corbo::DiscretizationGridInterface::DiscretizationGridInterface
DiscretizationGridInterface()=default
corbo::DiscretizationGridInterface::getFactory
static Factory< DiscretizationGridInterface > & getFactory()
Get access to the accociated factory.
Definition: discretization_grid_interface.h:128
corbo::DiscretizationGridInterface::Ptr
std::shared_ptr< DiscretizationGridInterface > Ptr
Definition: discretization_grid_interface.h:107
corbo::DiscretizationGridInterface::providesStateTrajectory
virtual bool providesStateTrajectory() const =0
corbo::DiscretizationGridInterface::setInitialDt
virtual void setInitialDt(double dt)=0
corbo::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
nlp_functions.h
corbo::ScalarVertex::setFixed
void setFixed(bool fixed)
Set vertex (un)fixed.
Definition: scalar_vertex.h:195
corbo::DiscretizationGridInterface::isTimeVariableGrid
virtual bool isTimeVariableGrid() const =0
time_series.h
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::DiscretizationGridInterface::getInitialDt
virtual double getInitialDt() const =0
corbo::ScalarVertex::value
const double & value() const
Get underlying value.
Definition: scalar_vertex.h:225
dynamics_eval_interface.h
corbo::DiscretizationGridInterface::computeActiveVertices
void computeActiveVertices() override=0
corbo::DiscretizationGridInterface::getN
virtual int getN() const =0
corbo::DiscretizationGridInterface::isUniformGrid
virtual bool isUniformGrid() const =0
types.h
corbo::DiscretizationGridInterface::getFinalTime
virtual double getFinalTime() const =0
corbo::Time
Representation of time stamps.
Definition: time.h:273
corbo::DiscretizationGridInterface::UPtr
std::unique_ptr< DiscretizationGridInterface > UPtr
Definition: discretization_grid_interface.h:108
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::GridUpdateResult::edges_updated
bool edges_updated
Definition: discretization_grid_interface.h:99
reference_trajectory.h
corbo::DiscretizationGridFactory
Factory< DiscretizationGridInterface > DiscretizationGridFactory
Definition: discretization_grid_interface.h:195
corbo::GridUpdateResult::updated
bool updated() const
Definition: discretization_grid_interface.h:101
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::VectorVertex::setFixed
virtual void setFixed(bool fixed)
Set complete vertex to fixed (and hence skip during optimization)
Definition: vector_vertex.h:254
vertex_set.h
corbo::VertexSetInterface::setModified
void setModified(bool modified)
Definition: vertex_set.h:126
corbo::GridUpdateResult::vertices_updated
bool vertices_updated
Definition: discretization_grid_interface.h:98
corbo::DiscretizationGridInterface::hasConstantControls
virtual bool hasConstantControls() const =0
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:45