Go to the documentation of this file.
23 #ifndef FULL_DISCRETIZATION_GRID_BASE_H_
24 #define FULL_DISCRETIZATION_GRID_BASE_H_
67 using Ptr = std::shared_ptr<FullDiscretizationGridBaseSE2>;
68 using UPtr = std::unique_ptr<FullDiscretizationGridBaseSE2>;
124 void clear()
override;
132 void setN(
int n,
bool try_resample =
true)
override;
143 int getN()
const override {
return _x_seq.size() + 1; }
175 int findClosestPose(
double x_ref,
double y_ref,
int start_idx = 0,
double* distance =
nullptr)
const;
180 void getVertices(std::vector<VertexInterface*>& vertices)
override;
208 std::vector<VectorVertexSE2>
_x_seq;
209 std::vector<VectorVertex>
_u_seq;
232 #endif // FULL_DISCRETIZATION_GRID_BASE_H_
std::unique_ptr< FullDiscretizationGridBaseSE2 > UPtr
double getDtRef() const
get current reference temporal resolution
void updateBounds(const NlpFunctions &nlp_fun)
virtual void resampleTrajectory(int n_new)
corbo::DiscretizationGridInterface::Ptr getInstance() const override=0
Return a newly created shared instance of the implemented class.
int getNRef() const
get reference horizon length
double getFinalTime() const override
bool getFirstControlInput(Eigen::VectorXd &u0) override
void setWarmStart(bool active)
activate or deactive warmstart
int findClosestPose(double x_ref, double y_ref, int start_idx=0, double *distance=nullptr) const
Find the closest pose (first part of the state vector) on the grid w.r.t. to a provided reference poi...
virtual void createEdges(NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics)=0
corbo::OptimizationEdgeSet OptimizationEdgeSet
int getInitialN() const override
std::vector< VectorVertex > _u_seq
bool isEmpty() const override
bool isTimeVariableGrid() const override
corbo::NlpFunctions NlpFunctions
bool hasConstantControls() const override
constexpr const double CORBO_INF_DBL
std::vector< VertexInterface * > _active_vertices
int findNearestState(const Eigen::VectorXd &x0)
virtual ~FullDiscretizationGridBaseSE2()=default
virtual bool adaptGrid(bool new_run, NlpFunctions &nlp_fun)
FullDiscretizationGridBaseSE2()=default
std::shared_ptr< DiscretizationGridInterface > Ptr
Eigen::VectorXd & values()
corbo::VertexInterface VertexInterface
PartiallyFixedVectorVertexSE2 _xf
bool isUniformGrid() const override
bool providesStateTrajectory() const override
void setDtRef(double dt)
set reference temporal resolution
CostIntegrationRule _cost_integration
virtual bool isGridAdaptActive() const
corbo::ScalarVertex ScalarVertex
bool checkAndInitializeXfFixedFlags(int dim_x)
corbo::PartiallyFixedVectorVertex PartiallyFixedVectorVertex
void setNRef(int n)
set reference horizon length
corbo::TimeSeries TimeSeries
corbo::ReferenceTrajectoryInterface ReferenceTrajectoryInterface
void setN(int n, bool try_resample=true) override
VectorVertexSE2 with support for partially fixed components.
std::shared_ptr< SystemDynamicsInterface > Ptr
corbo::GridUpdateResult update(const Eigen::VectorXd &x0, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun, OptimizationEdgeSet &edges, SystemDynamicsInterface::Ptr dynamics, bool new_run, const corbo::Time &t, ReferenceTrajectoryInterface *sref=nullptr, const Eigen::VectorXd *prev_u=nullptr, double prev_u_dt=0, ReferenceTrajectoryInterface *xinit=nullptr, ReferenceTrajectoryInterface *uinit=nullptr) override
Eigen::Matrix< bool, -1, 1 > _xf_fixed
const NlpFunctions * _nlp_fun
const Eigen::VectorXd & getState(int k) const
Return state at time stamp k.
std::shared_ptr< FiniteDifferencesCollocationInterface > Ptr
double getInitialDt() const override
virtual void warmStartShifting(const Eigen::VectorXd &x0)
virtual void initializeSequences(const Eigen::VectorXd &x0, const Eigen::VectorXd &xf, ReferenceTrajectoryInterface &uref, NlpFunctions &nlp_fun)
corbo::FiniteDifferencesCollocationInterface::Ptr _fd_eval
corbo::VectorVertex VectorVertex
void getVertices(std::vector< VertexInterface * > &vertices) override
double getFirstDt() const override
int getN() const override
get current horizon length
void setCostIntegrationRule(CostIntegrationRule integration)
Set cost integration rule.
corbo::SystemDynamicsInterface SystemDynamicsInterface
std::vector< VectorVertexSE2 > _x_seq
void getStateAndControlTimeSeries(TimeSeries::Ptr x_sequence, TimeSeries::Ptr u_sequence, double t_max=corbo::CORBO_INF_DBL) const override
virtual bool isDtFixedIntended() const
virtual bool isMovingHorizonWarmStartActive() const
std::shared_ptr< FullDiscretizationGridBaseSE2 > Ptr
std::vector< VertexInterface * > & getActiveVertices() override
void computeActiveVertices() override
void setXfFixed(const Eigen::Matrix< bool, -1, 1 > &xf_fixed)
Set individual components of the final state to fixed or unfixed.
std::shared_ptr< TimeSeries > Ptr
double getDt() const
get current temporal resolution
bool hasSingleDt() const override
virtual bool isValid() const
void setFiniteDifferencesCollocationMethod(corbo::FiniteDifferencesCollocationInterface::Ptr fd_eval)
Set finite differences collocation method.
void setModified(bool modified)
void setInitialDt(double dt) override
mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06