Vertex implementation that stores an Eigen::VectorXd (dynamic dimension) More...
#include <vector_vertex.h>
Public Types | |
using | Ptr = std::shared_ptr< VectorVertex > |
using | UPtr = std::unique_ptr< VectorVertex > |
![]() | |
using | Ptr = std::shared_ptr< VertexInterface > |
using | UPtr = std::unique_ptr< VertexInterface > |
Public Member Functions | |
void | clear () override |
Clear complete backup container. More... | |
void | discardTop () override |
Delete the previously made backup from the stack without restoring it. More... | |
const double * | getData () const override |
Get read-only raw access to the values of the vertex. More... | |
double * | getDataRaw () override |
Get write access to the values of the vertex. More... | |
int | getDimension () const override |
Return number of elements/values/components stored in this vertex. More... | |
int | getDimensionUnfixed () const override |
Return number of unfixed elements (unfixed elements are skipped as parameters in the Hessian and Jacobian. More... | |
const double * | getLowerBounds () const override |
Read-only raw access to lower bounds [getDimension() x 1]. More... | |
int | getNumBackups () const override |
Return the current size/number of backups of the backup stack. More... | |
int | getNumberFiniteBounds (bool unfixed_only) const override |
Get number of finite upper bounds (either upper or lower must be finite) More... | |
int | getNumberFiniteLowerBounds (bool unfixed_only) const override |
Get number of finite lower bounds. More... | |
int | getNumberFiniteUpperBounds (bool unfixed_only) const override |
Get number of finite upper bounds. More... | |
const double * | getUpperBounds () const override |
Read-only raw access to upper bounds [getDimension() x 1]. More... | |
bool | hasFiniteBounds () const override |
Check if finite bounds (lower or upper) are provided. More... | |
bool | hasFiniteLowerBound (int idx) const override |
Check if finite lower bound for a single component is provided. More... | |
bool | hasFiniteLowerBounds () const override |
Check if finite lower bounds are provided. More... | |
bool | hasFiniteUpperBound (int idx) const override |
Check if finite upper bound for a single component is provided. More... | |
bool | hasFiniteUpperBounds () const override |
Check if finite upper bounds are provided. More... | |
bool | hasFixedComponents () const override |
Check if the vertex has fixed components. More... | |
bool | isFixedComponent (int) const override |
Check if individual components are fixed or unfixed. More... | |
const Eigen::VectorXd & | lowerBound () const |
Read-access to the underlying lower bound vector. More... | |
void | plus (const double *inc) override |
Define the increment for the vertex: x += inc with dim(inc)=getDimension(). More... | |
void | plus (int idx, double inc) override |
Add value to a specific component of the vertex: x[idx] += inc. More... | |
void | plusUnfixed (const double *inc) override |
Define the increment for the unfixed components of the vertex: x += inc with dim(inc)=getDimensionUnfixed(). More... | |
void | pop () override |
Restore the previously stored values of the backup stack and remove them from the stack. More... | |
void | push () override |
Store all values into a internal backup stack. More... | |
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 |
Write data to to a specific component. More... | |
virtual void | setDimension (int dim) |
Change the dimension of the vertex (lower and upper bounds needs to be redefined) More... | |
virtual void | setFixed (bool fixed) |
Set complete vertex to fixed (and hence skip during optimization) More... | |
void | setLowerBound (int idx, double lb) override |
Define lower bound on a single component of the vertex (0 <= idx < getDimension()) More... | |
void | setLowerBounds (const Eigen::Ref< const Eigen::VectorXd > &lb) override |
Define lower bounds on the vertex values [getDimension() x 1]. More... | |
void | setUpperBound (int idx, double ub) override |
Define upper bound on a single component of the vertex (0 <= idx < getDimension()) More... | |
void | setUpperBounds (const Eigen::Ref< const Eigen::VectorXd > &ub) override |
Define upper bounds on the vertex values [getDimension() x 1]. More... | |
void | top () override |
Restore the previously stored values of the backup stack WITHOUT removing them from the stack. More... | |
const Eigen::VectorXd & | upperBound () const |
Read-access to the underlying upper bound vector. More... | |
Eigen::VectorXd & | values () |
Write-access to the underlying value vector. More... | |
const Eigen::VectorXd & | values () const |
Read-access to the underlying value vector. More... | |
VectorVertex ()=default | |
Default constructor. More... | |
VectorVertex (bool fixed) | |
VectorVertex (const Eigen::Ref< const Eigen::VectorXd > &values, bool fixed=false) | |
Construct vertex with given values. More... | |
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) | |
Construct vertex with given values, lower and upper bounds. More... | |
VectorVertex (int dimension, bool fixed=false) | |
Construct and allocate memory for a given dimension. More... | |
![]() | |
virtual void | clearBackups () |
void | clearConnectedEdges () |
Clear all connected edges. 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... | |
Eigen::Map< const Eigen::VectorXd > | getDataMap () const |
Get a read-only Eigen::Map to the values of the vertex. More... | |
Eigen::Map< Eigen::VectorXd > | getDataRawMap () |
Get a Eigen::Map to the values of the vertex. More... | |
Eigen::Map< const Eigen::VectorXd > | getLowerBoundsMap () const |
Read-only Eigen::Map for lower 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 | isFixed () const |
Check if all components are fixed. 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 | ~VertexInterface () |
Virtual destructor. More... | |
Protected Attributes | |
std::vector< Eigen::VectorXd > | _backup |
bool | _finite_lb_bounds = false |
bool | _finite_ub_bounds = false |
bool | _fixed = false |
Eigen::VectorXd | _lb |
Eigen::VectorXd | _ub |
Eigen::VectorXd | _values |
Vertex implementation that stores an Eigen::VectorXd (dynamic dimension)
The vertex can be either completely fixed or unfixed. In order to partially fix components of the underlying vector refer to class PartiallyFixedVectorVertex.
Definition at line 73 of file vector_vertex.h.
using corbo::VectorVertex::Ptr = std::shared_ptr<VectorVertex> |
Definition at line 98 of file vector_vertex.h.
using corbo::VectorVertex::UPtr = std::unique_ptr<VectorVertex> |
Definition at line 99 of file vector_vertex.h.
|
default |
Default constructor.
|
inlineexplicit |
Definition at line 104 of file vector_vertex.h.
|
inlineexplicit |
Construct and allocate memory for a given dimension.
Definition at line 107 of file vector_vertex.h.
|
inlineexplicit |
Construct vertex with given values.
Definition at line 118 of file vector_vertex.h.
|
inlineexplicit |
Construct vertex with given values, lower and upper bounds.
Definition at line 129 of file vector_vertex.h.
|
inlineoverridevirtual |
Clear complete backup container.
Implements corbo::VertexInterface.
Definition at line 279 of file vector_vertex.h.
|
inlineoverridevirtual |
Delete the previously made backup from the stack without restoring it.
Implements corbo::VertexInterface.
Definition at line 277 of file vector_vertex.h.
|
inlineoverridevirtual |
Get read-only raw access to the values of the vertex.
Implements corbo::VertexInterface.
Definition at line 161 of file vector_vertex.h.
|
inlineoverridevirtual |
Get write access to the values of the vertex.
Implements corbo::VertexInterface.
Definition at line 164 of file vector_vertex.h.
|
inlineoverridevirtual |
Return number of elements/values/components stored in this vertex.
Implements corbo::VertexInterface.
Definition at line 140 of file vector_vertex.h.
|
inlineoverridevirtual |
Return number of unfixed elements (unfixed elements are skipped as parameters in the Hessian and Jacobian.
Implements corbo::VertexInterface.
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 142 of file vector_vertex.h.
|
inlineoverridevirtual |
Read-only raw access to lower bounds [getDimension() x 1].
Implements corbo::VertexInterface.
Definition at line 257 of file vector_vertex.h.
|
inlineoverridevirtual |
Return the current size/number of backups of the backup stack.
Implements corbo::VertexInterface.
Definition at line 281 of file vector_vertex.h.
|
inlineoverridevirtual |
Get number of finite upper bounds (either upper or lower must be finite)
Implements corbo::VertexInterface.
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 245 of file vector_vertex.h.
|
inlineoverridevirtual |
Get number of finite lower bounds.
Implements corbo::VertexInterface.
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 230 of file vector_vertex.h.
|
inlineoverridevirtual |
Get number of finite upper bounds.
Implements corbo::VertexInterface.
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 238 of file vector_vertex.h.
|
inlineoverridevirtual |
Read-only raw access to upper bounds [getDimension() x 1].
Implements corbo::VertexInterface.
Definition at line 259 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if finite bounds (lower or upper) are provided.
Implements corbo::VertexInterface.
Definition at line 212 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if finite lower bound for a single component is provided.
Implements corbo::VertexInterface.
Definition at line 218 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if finite lower bounds are provided.
Implements corbo::VertexInterface.
Definition at line 214 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if finite upper bound for a single component is provided.
Implements corbo::VertexInterface.
Definition at line 224 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if finite upper bounds are provided.
Implements corbo::VertexInterface.
Definition at line 216 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if the vertex has fixed components.
Implements corbo::VertexInterface.
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 183 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if individual components are fixed or unfixed.
Implements corbo::VertexInterface.
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 185 of file vector_vertex.h.
|
inline |
Read-access to the underlying lower bound vector.
Definition at line 289 of file vector_vertex.h.
|
inlineoverridevirtual |
Define the increment for the vertex: x += inc with dim(inc)=getDimension().
Implements corbo::VertexInterface.
Definition at line 156 of file vector_vertex.h.
|
inlineoverridevirtual |
Add value to a specific component of the vertex: x[idx] += inc.
Implements corbo::VertexInterface.
Definition at line 154 of file vector_vertex.h.
|
inlineoverridevirtual |
Define the increment for the unfixed components of the vertex: x += inc with dim(inc)=getDimensionUnfixed().
Implements corbo::VertexInterface.
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 158 of file vector_vertex.h.
|
inlineoverridevirtual |
Restore the previously stored values of the backup stack and remove them from the stack.
Implements corbo::VertexInterface.
Definition at line 265 of file vector_vertex.h.
|
inlineoverridevirtual |
Store all values into a internal backup stack.
Implements corbo::VertexInterface.
Definition at line 263 of file vector_vertex.h.
|
inlinevirtual |
Set values and bounds at once.
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 170 of file vector_vertex.h.
|
inlineoverridevirtual |
Write data to to a specific component.
Implements corbo::VertexInterface.
Definition at line 167 of file vector_vertex.h.
|
inlinevirtual |
Change the dimension of the vertex (lower and upper bounds needs to be redefined)
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 145 of file vector_vertex.h.
|
inlinevirtual |
Set complete vertex to fixed (and hence skip during optimization)
Reimplemented in corbo::PartiallyFixedVectorVertex.
Definition at line 254 of file vector_vertex.h.
|
inlineoverridevirtual |
Define lower bound on a single component of the vertex (0 <= idx < getDimension())
Implements corbo::VertexInterface.
Definition at line 194 of file vector_vertex.h.
|
inlineoverridevirtual |
Define lower bounds on the vertex values [getDimension() x 1].
Implements corbo::VertexInterface.
Definition at line 188 of file vector_vertex.h.
|
inlineoverridevirtual |
Define upper bound on a single component of the vertex (0 <= idx < getDimension())
Implements corbo::VertexInterface.
Definition at line 206 of file vector_vertex.h.
|
inlineoverridevirtual |
Define upper bounds on the vertex values [getDimension() x 1].
Implements corbo::VertexInterface.
Definition at line 200 of file vector_vertex.h.
|
inlineoverridevirtual |
Restore the previously stored values of the backup stack WITHOUT removing them from the stack.
Implements corbo::VertexInterface.
Definition at line 271 of file vector_vertex.h.
|
inline |
Read-access to the underlying upper bound vector.
Definition at line 291 of file vector_vertex.h.
|
inline |
Write-access to the underlying value vector.
Definition at line 286 of file vector_vertex.h.
|
inline |
Read-access to the underlying value vector.
Definition at line 284 of file vector_vertex.h.
|
protected |
Definition at line 302 of file vector_vertex.h.
|
protected |
Definition at line 297 of file vector_vertex.h.
|
protected |
Definition at line 298 of file vector_vertex.h.
|
protected |
Definition at line 300 of file vector_vertex.h.
|
protected |
Definition at line 295 of file vector_vertex.h.
|
protected |
Definition at line 296 of file vector_vertex.h.
|
protected |
Definition at line 294 of file vector_vertex.h.