Generic interface class for vertices. More...
#include <vertex_interface.h>
Public Types | |
using | Ptr = std::shared_ptr< VertexInterface > |
using | UPtr = std::unique_ptr< VertexInterface > |
Public Member Functions | |
virtual void | clear ()=0 |
Clear complete backup container. More... | |
virtual void | clearBackups () |
void | clearConnectedEdges () |
Clear all connected edges. More... | |
virtual void | discardTop ()=0 |
Delete the previously made backup from the stack without restoring it. More... | |
const std::set< BaseEdge * > & | getConnectedEqualityEdgesRef () const |
Raw access for connected equality constraint edges. More... | |
const std::set< BaseEdge * > & | getConnectedInequalityEdgesRef () const |
Raw access for connected inequality constraint edges. More... | |
const std::set< BaseEdge * > & | getConnectedLsqObjectiveEdgesRef () const |
Raw access for connected least-squares objective edges. More... | |
const std::set< BaseMixedEdge * > & | getConnectedMixedEdgesRef () const |
Raw access for connected mixed edges. More... | |
const std::set< BaseEdge * > & | getConnectedObjectiveEdgesRef () const |
Raw access for connected objective edges. More... | |
virtual const double * | getData () const =0 |
Get read-only raw access to the values of the vertex. More... | |
Eigen::Map< const Eigen::VectorXd > | getDataMap () const |
Get a read-only Eigen::Map to the values of the vertex. More... | |
virtual double * | getDataRaw ()=0 |
Get write access to the values of the vertex. More... | |
Eigen::Map< Eigen::VectorXd > | getDataRawMap () |
Get a Eigen::Map to the values of the vertex. More... | |
virtual int | getDimension () const =0 |
Return number of elements/values/components stored in this vertex. More... | |
virtual int | getDimensionUnfixed () const =0 |
Return number of unfixed elements (unfixed elements are skipped as parameters in the Hessian and Jacobian. More... | |
virtual const double * | getLowerBounds () const =0 |
Read-only raw access to lower bounds [getDimension() x 1]. More... | |
Eigen::Map< const Eigen::VectorXd > | getLowerBoundsMap () const |
Read-only Eigen::Map for lower bounds [getDimension() x 1]. More... | |
virtual int | getNumBackups () const =0 |
Return the current size/number of backups of the backup stack. More... | |
virtual int | getNumberFiniteBounds (bool unfixed_only) const =0 |
Get number of finite upper bounds (either upper or lower must be finite) More... | |
virtual int | getNumberFiniteLowerBounds (bool unfixed_only) const =0 |
Get number of finite lower bounds. More... | |
virtual int | getNumberFiniteUpperBounds (bool unfixed_only) const =0 |
Get number of finite upper bounds. More... | |
virtual const double * | getUpperBounds () const =0 |
Read-only raw access to upper bounds [getDimension() x 1]. More... | |
Eigen::Map< const Eigen::VectorXd > | getUpperBoundsMap () const |
Read-only Eigen::Map for upper bounds [getDimension() x 1]. More... | |
int | getVertexIdx () const |
Retrieve current edge index (warning, this value is determined within the related VertexSetInterface implementation) More... | |
virtual bool | hasFiniteBounds () const =0 |
Check if finite bounds (lower or upper) are provided. More... | |
virtual bool | hasFiniteLowerBound (int idx) const =0 |
Check if finite lower bound for a single component is provided. More... | |
virtual bool | hasFiniteLowerBounds () const =0 |
Check if finite lower bounds are provided. More... | |
virtual bool | hasFiniteUpperBound (int idx) const =0 |
Check if finite upper bound for a single component is provided. More... | |
virtual bool | hasFiniteUpperBounds () const =0 |
Check if finite upper bounds are provided. More... | |
virtual bool | hasFixedComponents () const =0 |
Check if the vertex has fixed components. More... | |
virtual bool | isFixed () const |
Check if all components are fixed. More... | |
virtual bool | isFixedComponent (int idx) const =0 |
Check if individual components are fixed or unfixed. More... | |
virtual void | plus (int idx, double inc)=0 |
Add value to a specific component of the vertex: x[idx] += inc. More... | |
virtual void | plus (const double *inc)=0 |
Define the increment for the vertex: x += inc with dim(inc)=getDimension(). More... | |
virtual void | plusUnfixed (const double *inc)=0 |
Define the increment for the unfixed components of the vertex: x += inc with dim(inc)=getDimensionUnfixed(). More... | |
virtual void | pop ()=0 |
Restore the previously stored values of the backup stack and remove them from the stack. More... | |
virtual void | push ()=0 |
Store all values into a internal backup stack. More... | |
void | registerEqualityEdge (BaseEdge *edge) |
Register an adjacent equality constraint edge. More... | |
void | registerInequalityEdge (BaseEdge *edge) |
Register an adjacent inequality constraint edge. More... | |
void | registerLsqObjectiveEdge (BaseEdge *edge) |
Register an adjacent least-squares objective edge. More... | |
void | registerMixedEdge (BaseMixedEdge *edge) |
Register an adjacent mixed edge. More... | |
void | registerObjectiveEdge (BaseEdge *edge) |
Register an adjacent objective edge. More... | |
virtual void | setData (int idx, double data)=0 |
Write data to to a specific component. More... | |
virtual void | setLowerBound (int idx, double lb)=0 |
Define lower bound on a single component of the vertex (0 <= idx < getDimension()) More... | |
virtual void | setLowerBounds (const Eigen::Ref< const Eigen::VectorXd > &lb)=0 |
Define lower bounds on the vertex values [getDimension() x 1]. More... | |
virtual void | setUpperBound (int idx, double ub)=0 |
Define upper bound on a single component of the vertex (0 <= idx < getDimension()) More... | |
virtual void | setUpperBounds (const Eigen::Ref< const Eigen::VectorXd > &ub)=0 |
Define upper bounds on the vertex values [getDimension() x 1]. More... | |
virtual void | top ()=0 |
Restore the previously stored values of the backup stack WITHOUT removing them from the stack. More... | |
virtual | ~VertexInterface () |
Virtual destructor. More... | |
Private Attributes | |
std::set< BaseEdge * > | _edges_equalities |
connected equality constraint edges More... | |
std::set< BaseEdge * > | _edges_inequalities |
connected inequality constraint edges More... | |
std::set< BaseEdge * > | _edges_lsq_objective |
connected least-squares objective edges More... | |
std::set< BaseMixedEdge * > | _edges_mixed |
connected mixed edges More... | |
std::set< BaseEdge * > | _edges_objective |
Retrieve number of connected objective edges with custom Jacobian. More... | |
int | _vertex_idx = 0 |
vertex index in jacobian or hessian (determined by friend class HyperGraph). More... | |
Friends | |
class | VertexSetInterface |
Generic interface class for vertices.
This abstract class defines the interface for vertices. The optimization problem might be formulated as a hyper-graph in which optimization parameters are represented as vertices. Cost functions and constraints are represented as edges (refer to EdgeInterface).
Definition at line 53 of file vertex_interface.h.
using corbo::VertexInterface::Ptr = std::shared_ptr<VertexInterface> |
Definition at line 58 of file vertex_interface.h.
using corbo::VertexInterface::UPtr = std::unique_ptr<VertexInterface> |
Definition at line 59 of file vertex_interface.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 62 of file vertex_interface.h.
|
pure virtual |
Clear complete backup container.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
inlinevirtual |
Definition at line 167 of file vertex_interface.h.
|
inline |
Clear all connected edges.
Definition at line 82 of file vertex_interface.h.
|
pure virtual |
Delete the previously made backup from the stack without restoring it.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
inline |
Raw access for connected equality constraint edges.
Definition at line 155 of file vertex_interface.h.
|
inline |
Raw access for connected inequality constraint edges.
Definition at line 157 of file vertex_interface.h.
|
inline |
Raw access for connected least-squares objective edges.
Definition at line 153 of file vertex_interface.h.
|
inline |
Raw access for connected mixed edges.
Definition at line 159 of file vertex_interface.h.
|
inline |
Raw access for connected objective edges.
Definition at line 151 of file vertex_interface.h.
|
pure virtual |
Get read-only raw access to the values of the vertex.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
inline |
Get a read-only Eigen::Map to the values of the vertex.
Definition at line 103 of file vertex_interface.h.
|
pure virtual |
Get write access to the values of the vertex.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
inline |
Get a Eigen::Map to the values of the vertex.
Definition at line 105 of file vertex_interface.h.
|
pure virtual |
Return number of elements/values/components stored in this vertex.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Return number of unfixed elements (unfixed elements are skipped as parameters in the Hessian and Jacobian.
Implemented in corbo::PartiallyFixedVectorVertex, corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Read-only raw access to lower bounds [getDimension() x 1].
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
inline |
Read-only Eigen::Map for lower bounds [getDimension() x 1].
Definition at line 144 of file vertex_interface.h.
|
pure virtual |
Return the current size/number of backups of the backup stack.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Get number of finite upper bounds (either upper or lower must be finite)
Implemented in corbo::PartiallyFixedVectorVertex, corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Get number of finite lower bounds.
Implemented in corbo::PartiallyFixedVectorVertex, corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Get number of finite upper bounds.
Implemented in corbo::PartiallyFixedVectorVertex, corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Read-only raw access to upper bounds [getDimension() x 1].
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
inline |
Read-only Eigen::Map for upper bounds [getDimension() x 1].
Definition at line 148 of file vertex_interface.h.
|
inline |
Retrieve current edge index (warning, this value is determined within the related VertexSetInterface implementation)
Definition at line 172 of file vertex_interface.h.
|
pure virtual |
Check if finite bounds (lower or upper) are provided.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Check if finite lower bound for a single component is provided.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Check if finite lower bounds are provided.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Check if finite upper bound for a single component is provided.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Check if finite upper bounds are provided.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Check if the vertex has fixed components.
Implemented in corbo::PartiallyFixedVectorVertex, corbo::VectorVertex, and corbo::ScalarVertex.
|
inlinevirtual |
Check if all components are fixed.
Definition at line 69 of file vertex_interface.h.
|
pure virtual |
Check if individual components are fixed or unfixed.
Implemented in corbo::PartiallyFixedVectorVertex, corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Add value to a specific component of the vertex: x[idx] += inc.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Define the increment for the vertex: x += inc with dim(inc)=getDimension().
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Define the increment for the unfixed components of the vertex: x += inc with dim(inc)=getDimensionUnfixed().
Implemented in corbo::PartiallyFixedVectorVertex, corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Restore the previously stored values of the backup stack and remove them from the stack.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Store all values into a internal backup stack.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
void corbo::VertexInterface::registerEqualityEdge | ( | BaseEdge * | edge | ) |
Register an adjacent equality constraint edge.
Definition at line 33 of file vertex_interface.cpp.
void corbo::VertexInterface::registerInequalityEdge | ( | BaseEdge * | edge | ) |
Register an adjacent inequality constraint edge.
Definition at line 34 of file vertex_interface.cpp.
void corbo::VertexInterface::registerLsqObjectiveEdge | ( | BaseEdge * | edge | ) |
Register an adjacent least-squares objective edge.
Definition at line 32 of file vertex_interface.cpp.
void corbo::VertexInterface::registerMixedEdge | ( | BaseMixedEdge * | edge | ) |
Register an adjacent mixed edge.
Definition at line 35 of file vertex_interface.cpp.
void corbo::VertexInterface::registerObjectiveEdge | ( | BaseEdge * | edge | ) |
Register an adjacent objective edge.
Definition at line 31 of file vertex_interface.cpp.
|
pure virtual |
Write data to to a specific component.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Define lower bound on a single component of the vertex (0 <= idx < getDimension())
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Define lower bounds on the vertex values [getDimension() x 1].
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Define upper bound on a single component of the vertex (0 <= idx < getDimension())
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Define upper bounds on the vertex values [getDimension() x 1].
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
pure virtual |
Restore the previously stored values of the backup stack WITHOUT removing them from the stack.
Implemented in corbo::VectorVertex, and corbo::ScalarVertex.
|
friend |
Definition at line 55 of file vertex_interface.h.
|
private |
connected equality constraint edges
Definition at line 183 of file vertex_interface.h.
|
private |
connected inequality constraint edges
Definition at line 184 of file vertex_interface.h.
|
private |
connected least-squares objective edges
Definition at line 182 of file vertex_interface.h.
|
private |
connected mixed edges
Definition at line 185 of file vertex_interface.h.
|
private |
Retrieve number of connected objective edges with custom Jacobian.
Retrieve number of connected equality constraint edges with custom Jacobian Retrieve number of connected inequality constraint edges with custom Jacobian connected objective edges
Definition at line 181 of file vertex_interface.h.
|
private |
vertex index in jacobian or hessian (determined by friend class HyperGraph).
Definition at line 187 of file vertex_interface.h.