|
void | disableGridAdaptation () |
|
| FiniteDifferencesVariableGrid ()=default |
|
DiscretizationGridInterface::Ptr | getInstance () const override |
| Return a newly created shared instance of the implemented class. More...
|
|
void | setDtBounds (double dt_lb, double dt_ub) |
|
void | setGridAdaptSimpleShrinkingHorizon (bool adapt_first_iter=false) |
|
void | setGridAdaptTimeBasedAggressiveEstimate (int n_max, double dt_hyst_ratio=0.1, bool adapt_first_iter=false) |
|
void | setGridAdaptTimeBasedSingleStep (int n_max, double dt_hyst_ratio=0.1, bool adapt_first_iter=false) |
|
void | setNmin (int n_min) |
|
virtual | ~FiniteDifferencesVariableGrid ()=default |
|
| FiniteDifferencesGrid ()=default |
|
virtual | ~FiniteDifferencesGrid ()=default |
|
void | clear () override |
|
| FullDiscretizationGridBase ()=default |
|
std::vector< VertexInterface * > & | getActiveVertices () override |
|
double | getDt () const |
|
double | getDtRef () const |
|
double | getFinalTime () const override |
|
bool | getFirstControlInput (Eigen::VectorXd &u0) override |
|
double | getFirstDt () const override |
|
double | getInitialDt () const override |
|
int | getInitialN () const override |
|
int | getN () const override |
|
int | getNRef () const |
|
const Eigen::VectorXd & | getState (int k) const |
|
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) More...
|
|
void | getVertices (std::vector< VertexInterface *> &vertices) override |
|
bool | hasConstantControls () const override |
|
bool | hasSingleDt () const override |
|
bool | isEmpty () const override |
|
bool | isTimeVariableGrid () const override |
|
bool | isUniformGrid () const override |
|
virtual bool | isValid () const |
|
bool | providesStateTrajectory () const override |
|
void | setCostIntegrationRule (CostIntegrationRule integration) |
|
void | setDtRef (double dt) |
|
void | setFiniteDifferencesCollocationMethod (FiniteDifferencesCollocationInterface::Ptr fd_eval) |
|
void | setInitialDt (double dt) override |
|
void | setN (int n, bool try_resample=true) override |
| Return dimension of the control input dimension in the grid. More...
|
|
void | setNRef (int n) |
|
void | setWarmStart (bool active) |
|
void | setXfFixed (const Eigen::Matrix< bool, -1, 1 > &xf_fixed) |
|
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 |
|
virtual | ~FullDiscretizationGridBase ()=default |
|
| DiscretizationGridInterface ()=default |
|
| DiscretizationGridInterface (int state_dim, int control_dim) |
|
virtual | ~DiscretizationGridInterface ()=default |
| Virtual destructor. More...
|
|
void | applyIncrementNonFixed (const Eigen::Ref< const Eigen::VectorXd > &increment) |
| Active vertices related methods. More...
|
|
void | applyIncrementNonFixed (int idx, double increment) |
|
void | backupParametersActiveVertices () |
|
void | clearConnectedEdges () |
|
void | computeVertexIndices () |
| Precompute vertex indices in the hyper-graph (e.g. for the Jacobian or Hessian structure) More...
|
|
void | discardBackupParametersActiveVertices (bool all=false) |
|
void | getBounds (Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub) |
|
double | getLowerBound (int idx) |
|
int | getParameterDimension () |
|
double | getParameterValue (int idx) |
|
void | getParameterVector (Eigen::Ref< Eigen::VectorXd > x) |
|
double | getUpperBound (int idx) |
|
bool | isModified () const |
|
void | restoreBackupParametersActiveVertices (bool keep_backup) |
|
void | setBounds (const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub) |
|
void | setLowerBound (int idx, double lb) |
|
void | setModified (bool modified) |
|
void | setParameterValue (int idx, double x) |
|
void | setParameterVector (const Eigen::Ref< const Eigen::VectorXd > &x) |
|
void | setUpperBound (int idx, double ub) |
|
| VertexSetInterface () |
|
virtual | ~VertexSetInterface () |
| Virtual destructor. More...
|
|
|
bool | adaptGrid (bool new_run, NlpFunctions &nlp_fun) override |
|
bool | adaptGridSimpleShrinkingHorizon (NlpFunctions &nlp_fun) |
|
bool | adaptGridTimeBasedAggressiveEstimate (NlpFunctions &nlp_fun) |
|
bool | adaptGridTimeBasedSingleStep (NlpFunctions &nlp_fun) |
|
bool | isDtFixedIntended () const override |
|
bool | isGridAdaptActive () const override |
|
bool | isMovingHorizonWarmStartActive () const override |
|
void | createEdges (NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics) override |
|
bool | checkAndInitializeXfFixedFlags (int dim_x) |
|
void | computeActiveVertices () override |
|
int | findNearestState (const Eigen::VectorXd &x0) |
|
virtual void | initializeSequences (const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun) |
|
virtual void | initializeSequences (const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun) |
|
virtual void | resampleTrajectory (int n_new) |
|
void | updateBounds (const NlpFunctions &nlp_fun) |
|
virtual void | warmStartShifting (const Eigen::VectorXd &x0) |
|
void | setLastControlRef (const Eigen::VectorXd &last_u_ref) |
|
void | setPreviousControl (const Eigen::VectorXd &prev_u, double prev_u_dt) |
|
void | setVertexIdx (VertexInterface &vertex, int idx) |
|