#include <shooting_grid_base.h>
Classes | |
struct | ShootingInterval |
Public Types | |
using | Ptr = std::shared_ptr< ShootingGridBase > |
using | UPtr = std::unique_ptr< ShootingGridBase > |
![]() | |
using | Ptr = std::shared_ptr< DiscretizationGridInterface > |
using | UPtr = std::unique_ptr< DiscretizationGridInterface > |
![]() | |
using | Ptr = std::shared_ptr< VertexSetInterface > |
Public Member Functions | |
void | clear () override |
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 |
DiscretizationGridInterface::Ptr | getInstance () const override=0 |
Return a newly created shared instance of the implemented class. More... | |
int | getN () const override |
int | getNRef () 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 |
bool | isValid () const |
bool | providesStateTrajectory () const override |
void | setConsiderIntermediateStateConstraints (bool active) |
void | setDtRef (double dt) |
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 | setNumControlsPerShootingInterval (int num_u_per_interv) |
void | setNumControlsPerShootingInterval (int num_u_per_interv, bool intermediate_x_constraints) |
void | setNumericalIntegrator (NumericalIntegratorExplicitInterface::Ptr integrator) |
void | setWarmStart (bool active) |
void | setXfFixed (const Eigen::Matrix< bool, -1, 1 > &xf_fixed) |
ShootingGridBase ()=default | |
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 | ~ShootingGridBase ()=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... | |
Protected Member Functions | |
virtual bool | adaptGrid (bool new_run, NlpFunctions &nlp_fun) |
bool | checkAndInitializeXfFixedFlags (int dim_x) |
void | computeActiveVertices () override |
virtual void | createEdges (NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics)=0 |
int | findNearestShootingInterval (const Eigen::VectorXd &x0) |
void | initializeSequences (const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun) |
void | initializeSequences (const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun) |
virtual bool | isDtFixedIntended () const |
virtual bool | isGridAdaptActive () const |
virtual bool | isMovingHorizonWarmStartActive () const |
virtual bool | isXfShootingNode () const |
void | resampleTrajectory (int n_new, NlpFunctions &nlp_fun) |
void | updateBounds (const NlpFunctions &nlp_fun) |
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) |
Protected Attributes | |
std::vector< VertexInterface * > | _active_vertices |
ScalarVertex | _dt |
double | _dt_lb = 0 |
double | _dt_ref = 0.1 |
double | _dt_ub = CORBO_INF_DBL |
bool | _first_run = true |
bool | _full_discretization = true |
NumericalIntegratorExplicitInterface::Ptr | _integrator |
bool | _intermediate_x_constraints = false |
std::vector< ShootingInterval > | _intervals |
int | _n_adapt = 0 |
int | _n_ref = 11 |
int | _num_u_per_interv_ref = 1 |
bool | _warm_start = false |
PartiallyFixedVectorVertex | _xf |
Eigen::Matrix< bool, -1, 1 > | _xf_fixed |
![]() | |
VectorVertex | _u_prev |
ScalarVertex | _u_prev_dt |
VectorVertex | _u_ref |
![]() | |
bool | _modified = true |
Additional Inherited Members | |
![]() | |
static Factory< DiscretizationGridInterface > & | getFactory () |
Get access to the accociated factory. More... | |
Definition at line 39 of file shooting_grid_base.h.
using corbo::ShootingGridBase::Ptr = std::shared_ptr<ShootingGridBase> |
Definition at line 42 of file shooting_grid_base.h.
using corbo::ShootingGridBase::UPtr = std::unique_ptr<ShootingGridBase> |
Definition at line 43 of file shooting_grid_base.h.
|
default |
|
virtualdefault |
|
inlineprotectedvirtual |
Reimplemented in corbo::MultipleShootingVariableGrid.
Definition at line 129 of file shooting_grid_base.h.
|
protected |
Definition at line 426 of file shooting_grid_base.cpp.
|
overridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 556 of file shooting_grid_base.cpp.
|
overrideprotectedvirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 583 of file shooting_grid_base.cpp.
|
protectedpure virtual |
Implemented in corbo::MultipleShootingGrid.
|
protected |
Definition at line 356 of file shooting_grid_base.cpp.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 115 of file shooting_grid_base.h.
|
inline |
Definition at line 101 of file shooting_grid_base.h.
|
inline |
Definition at line 100 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 64 of file shooting_grid_base.h.
|
overridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 393 of file shooting_grid_base.cpp.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 63 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 87 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 88 of file shooting_grid_base.h.
|
overridepure virtual |
Return a newly created shared instance of the implemented class.
Implements corbo::DiscretizationGridInterface.
Implemented in corbo::MultipleShootingVariableGrid, and corbo::MultipleShootingGrid.
|
overridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 401 of file shooting_grid_base.cpp.
|
inline |
Definition at line 90 of file shooting_grid_base.h.
|
overridevirtual |
Return state and control trajectory as time series object (shared instance)
Implements corbo::DiscretizationGridInterface.
Definition at line 600 of file shooting_grid_base.cpp.
|
overridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 567 of file shooting_grid_base.cpp.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 66 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 67 of file shooting_grid_base.h.
|
protected |
Definition at line 141 of file shooting_grid_base.cpp.
|
protected |
Definition at line 216 of file shooting_grid_base.cpp.
|
inlineprotectedvirtual |
Reimplemented in corbo::MultipleShootingVariableGrid, and corbo::MultipleShootingGrid.
Definition at line 141 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 78 of file shooting_grid_base.h.
|
inlineprotectedvirtual |
Reimplemented in corbo::MultipleShootingVariableGrid.
Definition at line 143 of file shooting_grid_base.h.
|
inlineprotectedvirtual |
Reimplemented in corbo::MultipleShootingVariableGrid.
Definition at line 142 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 68 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 69 of file shooting_grid_base.h.
|
inline |
Definition at line 79 of file shooting_grid_base.h.
|
inlineprotectedvirtual |
Definition at line 148 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 70 of file shooting_grid_base.h.
|
protected |
Definition at line 473 of file shooting_grid_base.cpp.
|
inline |
Definition at line 104 of file shooting_grid_base.h.
|
inline |
Definition at line 99 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 86 of file shooting_grid_base.h.
|
inlineoverridevirtual |
Return dimension of the control input dimension in the grid.
Implements corbo::DiscretizationGridInterface.
Definition at line 81 of file shooting_grid_base.h.
void corbo::ShootingGridBase::setNRef | ( | int | n | ) |
Definition at line 412 of file shooting_grid_base.cpp.
|
inline |
Definition at line 92 of file shooting_grid_base.h.
|
inline |
Definition at line 93 of file shooting_grid_base.h.
|
inline |
Definition at line 106 of file shooting_grid_base.h.
|
inline |
Definition at line 102 of file shooting_grid_base.h.
|
inline |
Definition at line 108 of file shooting_grid_base.h.
|
overridevirtual |
Implements corbo::DiscretizationGridInterface.
Definition at line 39 of file shooting_grid_base.cpp.
|
protected |
Definition at line 441 of file shooting_grid_base.cpp.
|
protected |
Definition at line 292 of file shooting_grid_base.cpp.
|
protected |
Definition at line 155 of file shooting_grid_base.h.
|
protected |
Definition at line 153 of file shooting_grid_base.h.
|
protected |
Definition at line 167 of file shooting_grid_base.h.
|
protected |
Definition at line 160 of file shooting_grid_base.h.
|
protected |
Definition at line 168 of file shooting_grid_base.h.
|
protected |
Definition at line 163 of file shooting_grid_base.h.
|
protected |
Definition at line 170 of file shooting_grid_base.h.
|
protected |
Definition at line 150 of file shooting_grid_base.h.
|
protected |
Definition at line 171 of file shooting_grid_base.h.
|
protected |
Definition at line 152 of file shooting_grid_base.h.
|
protected |
Definition at line 159 of file shooting_grid_base.h.
|
protected |
Definition at line 158 of file shooting_grid_base.h.
|
protected |
Definition at line 157 of file shooting_grid_base.h.
|
protected |
Definition at line 162 of file shooting_grid_base.h.
|
protected |
Definition at line 154 of file shooting_grid_base.h.
|
protected |
Definition at line 166 of file shooting_grid_base.h.