|
void | clear () override=0 |
|
| DiscretizationGridInterface ()=default |
|
| DiscretizationGridInterface (int state_dim, int control_dim) |
|
virtual double | getFinalTime () const =0 |
|
virtual bool | getFirstControlInput (Eigen::VectorXd &u0)=0 |
|
virtual double | getFirstDt () const =0 |
|
virtual double | getInitialDt () const =0 |
|
virtual int | getInitialN () const =0 |
|
virtual Ptr | getInstance () const =0 |
| Return a newly created shared instance of the implemented class. More...
|
|
virtual int | getN () const =0 |
|
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) More...
|
|
virtual bool | hasConstantControls () const =0 |
|
virtual bool | hasSingleDt () const =0 |
|
virtual bool | isEmpty () const =0 |
|
virtual bool | isTimeVariableGrid () const =0 |
|
virtual bool | isUniformGrid () const =0 |
|
virtual bool | providesStateTrajectory () const =0 |
|
virtual void | setInitialDt (double dt)=0 |
|
virtual void | setN (int n, bool try_resample=true)=0 |
| Return dimension of the control input dimension in the grid. More...
|
|
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 |
|
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...
|
|
Generic interface class for discretization grids.
This abstract class defines the interface for discretization grids. Discretization grids represent state and control sequences subject to optimziation. Usually, in direct optimal control, continuous-time trajectories are discretized in order to transform the optimization problem into a finite parameter nonlinear optimization problem, also called nonlinear program.
A discretization grid directly interacts with a Hyper-Graph to define the optimal control problem. Hence, the grid provides the relevant vertices (optimization parameters) and the corresponding edge creation.
- See also
- HyperGraph
- Author
- Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)
Definition at line 82 of file discretization_grid_interface.h.