Public Member Functions | Public Attributes | List of all members
corbo::NlpFunctions Class Reference

#include <nlp_functions.h>

Public Member Functions

void checkAndInitializeBoundDimensions (int x_dim, int u_dim)
 
void clear ()
 
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)
 
BaseEdge::Ptr getFinalStateConstraintEdge (int k, VectorVertex &xf)
 
BaseEdge::Ptr getFinalStateCostEdge (int k, VectorVertex &xf)
 
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)
 
void getNonIntegralStageFunctionEdges (int k, VectorVertex &xk, VectorVertex &uk, ScalarVertex &dt, 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)
 
bool hasIntegralTerms (int k) const
 
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)
 

Public Attributes

FinalStageConstraint::Ptr final_stage_constraints
 
FinalStageCost::Ptr final_stage_cost
 
StageCost::Ptr stage_cost
 
StageEqualityConstraint::Ptr stage_equalities
 
StageInequalityConstraint::Ptr stage_inequalities
 
StagePreprocessor::Ptr stage_preprocessor
 
Eigen::VectorXd u_lb
 
Eigen::VectorXd u_ub
 
Eigen::VectorXd x_lb
 
Eigen::VectorXd x_ub
 

Detailed Description

Definition at line 36 of file nlp_functions.h.

Member Function Documentation

◆ checkAndInitializeBoundDimensions()

void corbo::NlpFunctions::checkAndInitializeBoundDimensions ( int  x_dim,
int  u_dim 
)

Definition at line 47 of file nlp_functions.cpp.

◆ clear()

void corbo::NlpFunctions::clear ( )
inline

Definition at line 81 of file nlp_functions.h.

◆ getFinalControlDeviationEdges()

void corbo::NlpFunctions::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 at line 152 of file nlp_functions.cpp.

◆ getFinalStateConstraintEdge()

BaseEdge::Ptr corbo::NlpFunctions::getFinalStateConstraintEdge ( int  k,
VectorVertex xf 
)

Definition at line 204 of file nlp_functions.cpp.

◆ getFinalStateCostEdge()

BaseEdge::Ptr corbo::NlpFunctions::getFinalStateCostEdge ( int  k,
VectorVertex xf 
)

Definition at line 188 of file nlp_functions.cpp.

◆ getNonIntegralStageFunctionEdges() [1/2]

void corbo::NlpFunctions::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 at line 70 of file nlp_functions.cpp.

◆ getNonIntegralStageFunctionEdges() [2/2]

void corbo::NlpFunctions::getNonIntegralStageFunctionEdges ( int  k,
VectorVertex xk,
VectorVertex uk,
ScalarVertex dt,
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 at line 134 of file nlp_functions.cpp.

◆ hasIntegralTerms()

bool corbo::NlpFunctions::hasIntegralTerms ( int  k) const
inline

Definition at line 73 of file nlp_functions.h.

◆ update()

bool corbo::NlpFunctions::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 at line 31 of file nlp_functions.cpp.

Member Data Documentation

◆ final_stage_constraints

FinalStageConstraint::Ptr corbo::NlpFunctions::final_stage_constraints

Definition at line 43 of file nlp_functions.h.

◆ final_stage_cost

FinalStageCost::Ptr corbo::NlpFunctions::final_stage_cost

Definition at line 40 of file nlp_functions.h.

◆ stage_cost

StageCost::Ptr corbo::NlpFunctions::stage_cost

Definition at line 39 of file nlp_functions.h.

◆ stage_equalities

StageEqualityConstraint::Ptr corbo::NlpFunctions::stage_equalities

Definition at line 41 of file nlp_functions.h.

◆ stage_inequalities

StageInequalityConstraint::Ptr corbo::NlpFunctions::stage_inequalities

Definition at line 42 of file nlp_functions.h.

◆ stage_preprocessor

StagePreprocessor::Ptr corbo::NlpFunctions::stage_preprocessor

Definition at line 44 of file nlp_functions.h.

◆ u_lb

Eigen::VectorXd corbo::NlpFunctions::u_lb

Definition at line 48 of file nlp_functions.h.

◆ u_ub

Eigen::VectorXd corbo::NlpFunctions::u_ub

Definition at line 49 of file nlp_functions.h.

◆ x_lb

Eigen::VectorXd corbo::NlpFunctions::x_lb

Definition at line 46 of file nlp_functions.h.

◆ x_ub

Eigen::VectorXd corbo::NlpFunctions::x_ub

Definition at line 47 of file nlp_functions.h.


The documentation for this class was generated from the following files:


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03