Vertex specialization for vectors in SE2. More...
#include <vector_vertex_se2.h>
Public Types | |
using | Ptr = std::shared_ptr< VectorVertexSE2 > |
using | UPtr = std::unique_ptr< VectorVertexSE2 > |
![]() | |
typedef std::shared_ptr< VectorVertex > | Ptr |
typedef std::unique_ptr< VectorVertex > | UPtr |
![]() | |
typedef std::shared_ptr< VertexInterface > | Ptr |
typedef std::unique_ptr< VertexInterface > | UPtr |
Public Member Functions | |
void | plus (const double *inc) override |
void | plus (int idx, double inc) override |
void | plusUnfixed (const double *inc) override |
virtual void | set (const Eigen::Ref< const Eigen::VectorXd > &values, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, bool fixed=false) |
Set values and bounds at once. More... | |
void | setData (int idx, double data) override |
VectorVertexSE2 ()=default | |
Default constructor. More... | |
VectorVertexSE2 (bool fixed) | |
VectorVertexSE2 (const Eigen::Ref< const Eigen::VectorXd > &values, bool fixed=false) | |
Construct vertex with given values. More... | |
VectorVertexSE2 (const Eigen::Ref< const Eigen::VectorXd > &values, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, bool fixed=false) | |
Construct vertex with given values, lower and upper bounds. More... | |
VectorVertexSE2 (int dimension, bool fixed=false) | |
Construct and allocate memory for a given dimension. More... | |
![]() | |
void | clear () override |
void | discardTop () override |
const double * | getData () const override |
double * | getDataRaw () override |
int | getDimension () const override |
int | getDimensionUnfixed () const override |
const double * | getLowerBounds () const override |
int | getNumBackups () const override |
int | getNumberFiniteBounds (bool unfixed_only) const override |
int | getNumberFiniteLowerBounds (bool unfixed_only) const override |
int | getNumberFiniteUpperBounds (bool unfixed_only) const override |
const double * | getUpperBounds () const override |
bool | hasFiniteBounds () const override |
bool | hasFiniteLowerBound (int idx) const override |
bool | hasFiniteLowerBounds () const override |
bool | hasFiniteUpperBound (int idx) const override |
bool | hasFiniteUpperBounds () const override |
bool | hasFixedComponents () const override |
bool | isFixedComponent (int) const override |
const Eigen::VectorXd & | lowerBound () const |
void | pop () override |
void | push () override |
virtual void | setDimension (int dim) |
virtual void | setFixed (bool fixed) |
void | setLowerBound (int idx, double lb) override |
void | setLowerBounds (const Eigen::Ref< const Eigen::VectorXd > &lb) override |
void | setUpperBound (int idx, double ub) override |
void | setUpperBounds (const Eigen::Ref< const Eigen::VectorXd > &ub) override |
void | top () override |
const Eigen::VectorXd & | upperBound () const |
Eigen::VectorXd & | values () |
const Eigen::VectorXd & | values () const |
VectorVertex ()=default | |
VectorVertex (bool fixed) | |
VectorVertex (const Eigen::Ref< const Eigen::VectorXd > &values, bool fixed=false) | |
VectorVertex (const Eigen::Ref< const Eigen::VectorXd > &values, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, bool fixed=false) | |
VectorVertex (int dimension, bool fixed=false) | |
![]() | |
virtual void | clearBackups () |
void | clearConnectedEdges () |
const std::set< BaseEdge * > & | getConnectedEqualityEdgesRef () const |
const std::set< BaseEdge * > & | getConnectedInequalityEdgesRef () const |
const std::set< BaseEdge * > & | getConnectedLsqObjectiveEdgesRef () const |
const std::set< BaseMixedEdge * > & | getConnectedMixedEdgesRef () const |
const std::set< BaseEdge * > & | getConnectedObjectiveEdgesRef () const |
Eigen::Map< const Eigen::VectorXd > | getDataMap () const |
Eigen::Map< Eigen::VectorXd > | getDataRawMap () |
Eigen::Map< const Eigen::VectorXd > | getLowerBoundsMap () const |
Eigen::Map< const Eigen::VectorXd > | getUpperBoundsMap () const |
int | getVertexIdx () const |
virtual bool | isFixed () const |
void | registerEqualityEdge (BaseEdge *edge) |
void | registerInequalityEdge (BaseEdge *edge) |
void | registerLsqObjectiveEdge (BaseEdge *edge) |
void | registerMixedEdge (BaseMixedEdge *edge) |
void | registerObjectiveEdge (BaseEdge *edge) |
virtual | ~VertexInterface () |
Additional Inherited Members | |
![]() | |
std::vector< Eigen::VectorXd > | _backup |
bool | _finite_lb_bounds |
bool | _finite_ub_bounds |
bool | _fixed |
Eigen::VectorXd | _lb |
Eigen::VectorXd | _ub |
Eigen::VectorXd | _values |
Vertex specialization for vectors in SE2.
This class defines a vector vertex in which the first three components must be defined in SE2. Whereas the first two states are ordinary real numbers on (-inf, inf), the third component must remain in [-pi, pi).
The minimum dimension of this vertex is 3. This vertex allows for larger dimensions of 3, but these components are considered as standard real numbers on (-inf, inf).
Definition at line 74 of file vector_vertex_se2.h.
using mpc_local_planner::VectorVertexSE2::Ptr = std::shared_ptr<VectorVertexSE2> |
Definition at line 97 of file vector_vertex_se2.h.
using mpc_local_planner::VectorVertexSE2::UPtr = std::unique_ptr<VectorVertexSE2> |
Definition at line 98 of file vector_vertex_se2.h.
|
default |
Default constructor.
|
inlineexplicit |
Definition at line 103 of file vector_vertex_se2.h.
|
inlineexplicit |
Construct and allocate memory for a given dimension.
Definition at line 106 of file vector_vertex_se2.h.
|
inlineexplicit |
Construct vertex with given values.
Definition at line 109 of file vector_vertex_se2.h.
|
inlineexplicit |
Construct vertex with given values, lower and upper bounds.
Definition at line 112 of file vector_vertex_se2.h.
|
inlineoverridevirtual |
Reimplemented from corbo::VectorVertex.
Definition at line 127 of file vector_vertex_se2.h.
|
inlineoverridevirtual |
Reimplemented from corbo::VectorVertex.
Definition at line 119 of file vector_vertex_se2.h.
|
inlineoverridevirtual |
Reimplemented from corbo::VectorVertex.
Reimplemented in mpc_local_planner::PartiallyFixedVectorVertexSE2.
Definition at line 136 of file vector_vertex_se2.h.
|
inlinevirtual |
Set values and bounds at once.
Reimplemented from corbo::VectorVertex.
Reimplemented in mpc_local_planner::PartiallyFixedVectorVertexSE2.
Definition at line 148 of file vector_vertex_se2.h.
|
inlineoverridevirtual |
Reimplemented from corbo::VectorVertex.
Definition at line 139 of file vector_vertex_se2.h.