nlp_functions.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_FUNCTIONS_NLP_FUNCTIONS_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_FUNCTIONS_NLP_FUNCTIONS_H_
27 
29 
30 #include <memory>
31 
32 namespace corbo {
33 
34 class DiscretizationGridInterface;
35 
36 class NlpFunctions
37 {
38  public:
45 
46  Eigen::VectorXd x_lb;
47  Eigen::VectorXd x_ub;
48  Eigen::VectorXd u_lb;
49  Eigen::VectorXd u_ub;
50 
51  // TODO(roesmann): do we really need sref here? can we add that to the particular cost functions that require it?
52  // TODO(roesmann): Actually, I don't like the single_dt information here. Is there a more abstract way? Uniform grid?
53  bool update(int n, double t, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, ReferenceTrajectoryInterface* sref,
54  bool single_dt, const Eigen::VectorXd& x0, const std::vector<double>& dts, const DiscretizationGridInterface* grid);
55 
56  // TODO(roesmann) this complete nlp function vs edges stuff could definitely need a redesign...
57  void getNonIntegralStageFunctionEdges(int k, VectorVertex& xk, VectorVertex& uk, ScalarVertex& dt, VectorVertex& u_prev, ScalarVertex& u_prev_dt,
58  const StageFunction& stage_fun, std::vector<BaseEdge::Ptr>& edges);
59 
61  std::vector<BaseEdge::Ptr>& cost_edges, std::vector<BaseEdge::Ptr>& eq_edges,
62  std::vector<BaseEdge::Ptr>& ineq_edges);
63 
64  void getFinalControlDeviationEdges(int n, VectorVertex& u_ref, VectorVertex& u_prev, ScalarVertex& u_prev_dt,
65  std::vector<BaseEdge::Ptr>& cost_edges, std::vector<BaseEdge::Ptr>& eq_edges,
66  std::vector<BaseEdge::Ptr>& ineq_edges);
67 
70 
71  void checkAndInitializeBoundDimensions(int x_dim, int u_dim);
72 
73  bool hasIntegralTerms(int k) const
74  {
75  if (stage_cost && stage_cost->hasIntegralTerms(k)) return true;
76  if (stage_equalities && stage_equalities->hasIntegralTerms(k)) return true;
77  if (stage_inequalities && stage_inequalities->hasIntegralTerms(k)) return true;
78  return false;
79  }
80 
81  void clear()
82  {
83  stage_cost.reset();
84  final_stage_cost.reset();
85  stage_equalities.reset();
86  stage_inequalities.reset();
88  stage_preprocessor.reset();
89 
90  x_lb = Eigen::VectorXd();
91  x_ub = Eigen::VectorXd();
92  u_lb = Eigen::VectorXd();
93  u_ub = Eigen::VectorXd();
94  }
95 };
96 
97 } // namespace corbo
98 
99 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_FUNCTIONS_NLP_FUNCTIONS_H_
corbo::NlpFunctions::clear
void clear()
Definition: nlp_functions.h:103
corbo::NlpFunctions::stage_inequalities
StageInequalityConstraint::Ptr stage_inequalities
Definition: nlp_functions.h:64
corbo::StagePreprocessor::Ptr
std::shared_ptr< StagePreprocessor > Ptr
Definition: stage_preprocessor.h:66
corbo::NlpFunctions::hasIntegralTerms
bool hasIntegralTerms(int k) const
Definition: nlp_functions.h:95
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::NlpFunctions::x_ub
Eigen::VectorXd x_ub
Definition: nlp_functions.h:69
corbo::StageInequalityConstraint::Ptr
std::shared_ptr< StageInequalityConstraint > Ptr
Definition: stage_functions.h:319
corbo::NlpFunctions::stage_cost
StageCost::Ptr stage_cost
Definition: nlp_functions.h:61
corbo::NlpFunctions::checkAndInitializeBoundDimensions
void checkAndInitializeBoundDimensions(int x_dim, int u_dim)
Definition: nlp_functions.cpp:69
corbo::NlpFunctions::getFinalStateCostEdge
BaseEdge::Ptr getFinalStateCostEdge(int k, VectorVertex &xf)
Definition: nlp_functions.cpp:210
corbo::NlpFunctions::final_stage_constraints
FinalStageConstraint::Ptr final_stage_constraints
Definition: nlp_functions.h:65
corbo::StageCost::Ptr
std::shared_ptr< StageCost > Ptr
Definition: stage_functions.h:155
corbo::NlpFunctions::u_ub
Eigen::VectorXd u_ub
Definition: nlp_functions.h:71
corbo::NlpFunctions::x_lb
Eigen::VectorXd x_lb
Definition: nlp_functions.h:68
corbo::NlpFunctions::stage_equalities
StageEqualityConstraint::Ptr stage_equalities
Definition: nlp_functions.h:63
corbo::BaseEdge::Ptr
std::shared_ptr< BaseEdge > Ptr
Definition: edge_interface.h:134
corbo::NlpFunctions::u_lb
Eigen::VectorXd u_lb
Definition: nlp_functions.h:70
stage_functions.h
corbo::FinalStageConstraint::Ptr
std::shared_ptr< FinalStageConstraint > Ptr
Definition: stage_functions.h:227
corbo::NlpFunctions::stage_preprocessor
StagePreprocessor::Ptr stage_preprocessor
Definition: nlp_functions.h:66
corbo::NlpFunctions::update
bool update(int n, double t, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, ReferenceTrajectoryInterface *sref, bool single_dt, const Eigen::VectorXd &x0, const std::vector< double > &dts, const DiscretizationGridInterface *grid)
Definition: nlp_functions.cpp:53
corbo::StageFunction
Definition: stage_functions.h:69
corbo::NlpFunctions::getFinalControlDeviationEdges
void getFinalControlDeviationEdges(int n, VectorVertex &u_ref, VectorVertex &u_prev, ScalarVertex &u_prev_dt, std::vector< BaseEdge::Ptr > &cost_edges, std::vector< BaseEdge::Ptr > &eq_edges, std::vector< BaseEdge::Ptr > &ineq_edges)
Definition: nlp_functions.cpp:174
corbo::ScalarVertex
Vertex implementation for scalar values.
Definition: scalar_vertex.h:72
corbo::FinalStageCost::Ptr
std::shared_ptr< FinalStageCost > Ptr
Definition: stage_functions.h:175
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::VectorVertex
Vertex implementation that stores an Eigen::VectorXd (dynamic dimension)
Definition: vector_vertex.h:73
corbo::NlpFunctions::getNonIntegralStageFunctionEdges
void getNonIntegralStageFunctionEdges(int k, VectorVertex &xk, VectorVertex &uk, ScalarVertex &dt, VectorVertex &u_prev, ScalarVertex &u_prev_dt, const StageFunction &stage_fun, std::vector< BaseEdge::Ptr > &edges)
Definition: nlp_functions.cpp:92
corbo::NlpFunctions::final_stage_cost
FinalStageCost::Ptr final_stage_cost
Definition: nlp_functions.h:62
corbo::StageEqualityConstraint::Ptr
std::shared_ptr< StageEqualityConstraint > Ptr
Definition: stage_functions.h:301
corbo::NlpFunctions::getFinalStateConstraintEdge
BaseEdge::Ptr getFinalStateConstraintEdge(int k, VectorVertex &xf)
Definition: nlp_functions.cpp:226


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