Go to the documentation of this file.
25 #ifndef SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_DISCRETIZATION_GRIDS_SHOOTING_GRID_BASE_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_DISCRETIZATION_GRIDS_SHOOTING_GRID_BASE_H_
39 class ShootingGridBase :
public DiscretizationGridInterface
42 using Ptr = std::shared_ptr<ShootingGridBase>;
43 using UPtr = std::unique_ptr<ShootingGridBase>;
45 struct ShootingInterval
48 std::vector<VectorVertex>
u_seq;
58 GridUpdateResult
update(
const Eigen::VectorXd& x0, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, NlpFunctions& nlp_fun,
60 ReferenceTrajectoryInterface* sref =
nullptr,
const Eigen::VectorXd* prev_u =
nullptr,
double prev_u_dt = 0,
76 void clear()
override;
81 void setN(
int n,
bool try_resample =
true)
override
116 void getVertices(std::vector<VertexInterface*>& vertices)
override;
118 #ifdef MESSAGE_SUPPORT
119 void fromMessage(
const messages::DiscretizationGrid& message, std::stringstream* issues)
override {}
120 void toMessage(messages::DiscretizationGrid& message)
const override {}
176 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_DISCRETIZATION_GRIDS_SHOOTING_GRID_BASE_H_
virtual bool adaptGrid(bool new_run, NlpFunctions &nlp_fun)
NumericalIntegratorExplicitInterface::Ptr _integrator
bool isEmpty() const override
int _num_u_per_interv_ref
bool providesStateTrajectory() const override
std::vector< ShootingInterval > _intervals
void setWarmStart(bool active)
Interface class for reference trajectories.
bool getFirstControlInput(Eigen::VectorXd &u0) override
std::shared_ptr< NumericalIntegratorExplicitInterface > Ptr
void setInitialDt(double dt) override
void getVertices(std::vector< VertexInterface * > &vertices) override
ShootingGridBase()=default
void warmStartShifting(const Eigen::VectorXd &x0)
constexpr const double CORBO_INF_DBL
Representation for infinity (double version)
double getFinalTime() const override
virtual bool isGridAdaptActive() const
virtual ~ShootingGridBase()=default
bool hasConstantControls() const override
PartiallyFixedVectorVertex _xf
std::shared_ptr< DiscretizationGridInterface > Ptr
Eigen::Matrix< bool, -1, 1 > _xf_fixed
bool isTimeVariableGrid() const override
DiscretizationGridInterface::Ptr getInstance() const override=0
Return a newly created shared instance of the implemented class.
std::vector< VertexInterface * > & getActiveVertices() override
int getN() const override
virtual bool isDtFixedIntended() const
int findNearestShootingInterval(const Eigen::VectorXd &x0)
void computeActiveVertices() override
bool isUniformGrid() const override
void setConsiderIntermediateStateConstraints(bool active)
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
std::shared_ptr< SystemDynamicsInterface > Ptr
void resampleTrajectory(int n_new, NlpFunctions &nlp_fun)
void setXfFixed(const Eigen::Matrix< bool, -1, 1 > &xf_fixed)
virtual bool isMovingHorizonWarmStartActive() const
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
double getFirstDt() const override
const double & value() const
Get underlying value.
void setNumericalIntegrator(NumericalIntegratorExplicitInterface::Ptr integrator)
virtual void createEdges(NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics)=0
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)
Vertex implementation for scalar values.
double getInitialDt() const override
std::vector< VertexInterface * > _active_vertices
void initializeSequences(const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun)
int getInitialN() const override
std::shared_ptr< TimeSeries > Ptr
bool checkAndInitializeXfFixedFlags(int dim_x)
void setNumControlsPerShootingInterval(int num_u_per_interv)
bool _full_discretization
virtual bool isXfShootingNode() const
std::vector< VectorVertex > u_seq
void setModified(bool modified)
bool hasSingleDt() const override
void setN(int n, bool try_resample=true) override
Return dimension of the control input dimension in the grid.
Vector based vertex with support for partially fixed components.
bool _intermediate_x_constraints
std::unique_ptr< ShootingGridBase > UPtr
void updateBounds(const NlpFunctions &nlp_fun)
std::shared_ptr< ShootingGridBase > Ptr
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:12