Vector based vertex with support for partially fixed components. More...
#include <vector_vertex.h>
Public Types | |
using | Ptr = std::shared_ptr< PartiallyFixedVectorVertex > |
using | UPtr = std::unique_ptr< PartiallyFixedVectorVertex > |
![]() | |
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 | |
const Eigen::Array< bool, -1, 1 > | fixedArray () const |
Read-only access to the underlying logical array for fixed components. More... | |
int | getDimensionUnfixed () const override |
Return number of unfixed elements (unfixed elements are skipped as parameters in the Hessian and Jacobian. 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... | |
bool | hasFixedComponents () const override |
Check if the vertex has fixed components. More... | |
bool | isFixedComponent (int idx) const override |
Check if individual components are fixed or unfixed. More... | |
PartiallyFixedVectorVertex ()=default | |
Default constructor. More... | |
PartiallyFixedVectorVertex (int dimension) | |
PartiallyFixedVectorVertex (int dimension, const Eigen::Ref< const Eigen::Array< bool, -1, 1 >> &fixed) | |
Construct and allocate memory for a given dimension. More... | |
PartiallyFixedVectorVertex (const Eigen::Ref< const Eigen::VectorXd > &values) | |
Construct vertex with given values. More... | |
PartiallyFixedVectorVertex (const Eigen::Ref< const Eigen::VectorXd > &values, const Eigen::Ref< const Eigen::Array< bool, -1, 1 >> &fixed) | |
Construct vertex with given values and fixed components. More... | |
PartiallyFixedVectorVertex (const Eigen::Ref< const Eigen::VectorXd > &values, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub) | |
Construct vertex with given values, lower and upper bounds. 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 | 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) override |
Set values and bounds at once. More... | |
void | set (const Eigen::Ref< const Eigen::VectorXd > &values, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, const Eigen::Ref< const Eigen::Array< bool, -1, 1 >> &fixed) |
Set values and bounds at once (overload with fixed vector) More... | |
void | setDimension (int dim) override |
Change the dimension of the vertex (lower and upper bounds needs to be redefined) More... | |
void | setFixed (int idx, bool fixed) |
Set component with idx (0 <= idx < dimension()) to (un)fixed. More... | |
void | setFixed (const Eigen::Ref< const Eigen::Array< bool, -1, 1 >> &fixed) |
Set logical array [dimension() x 1] in order to fix selected components. More... | |
void | setFixed (bool fixed) override |
Set complete vertex to fixed (and hence skip during optimization) More... | |
![]() | |
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... | |
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... | |
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... | |
const Eigen::VectorXd & | lowerBound () const |
Read-access to the underlying lower bound vector. More... | |
void | plus (int idx, double inc) override |
Add value to a specific component of the vertex: x[idx] += inc. More... | |
void | plus (const double *inc) override |
Define the increment for the vertex: x += inc with dim(inc)=getDimension(). 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... | |
void | setData (int idx, double data) override |
Write data to to a specific component. 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... | |
const Eigen::VectorXd & | values () const |
Read-access to the underlying value vector. More... | |
Eigen::VectorXd & | values () |
Write-access to the underlying value vector. More... | |
VectorVertex ()=default | |
Default constructor. More... | |
VectorVertex (bool fixed) | |
VectorVertex (int dimension, bool fixed=false) | |
Construct and allocate memory for a given dimension. More... | |
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... | |
![]() | |
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 | |
Eigen::Array< bool, -1, 1 > | _fixed |
int | _num_unfixed |
![]() | |
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 |
Vector based vertex with support for partially fixed components.
The vertex extends VectorVertex by allowing the user to partially fix components of the underlying vector.
Definition at line 276 of file vector_vertex.h.
using corbo::PartiallyFixedVectorVertex::Ptr = std::shared_ptr<PartiallyFixedVectorVertex> |
Definition at line 279 of file vector_vertex.h.
using corbo::PartiallyFixedVectorVertex::UPtr = std::unique_ptr<PartiallyFixedVectorVertex> |
Definition at line 280 of file vector_vertex.h.
|
default |
Default constructor.
|
inlineexplicit |
Definition at line 285 of file vector_vertex.h.
|
inlineexplicit |
Construct and allocate memory for a given dimension.
Definition at line 291 of file vector_vertex.h.
|
inlineexplicit |
Construct vertex with given values.
Definition at line 297 of file vector_vertex.h.
|
inlineexplicit |
Construct vertex with given values and fixed components.
Definition at line 303 of file vector_vertex.h.
|
inlineexplicit |
Construct vertex with given values, lower and upper bounds.
Definition at line 309 of file vector_vertex.h.
|
inline |
Read-only access to the underlying logical array for fixed components.
Definition at line 441 of file vector_vertex.h.
|
inlineoverridevirtual |
Return number of unfixed elements (unfixed elements are skipped as parameters in the Hessian and Jacobian.
Reimplemented from corbo::VectorVertex.
Definition at line 316 of file vector_vertex.h.
|
inlineoverridevirtual |
Get number of finite upper bounds (either upper or lower must be finite)
Reimplemented from corbo::VectorVertex.
Definition at line 425 of file vector_vertex.h.
|
inlineoverridevirtual |
Get number of finite lower bounds.
Reimplemented from corbo::VectorVertex.
Definition at line 393 of file vector_vertex.h.
|
inlineoverridevirtual |
Get number of finite upper bounds.
Reimplemented from corbo::VectorVertex.
Definition at line 409 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if the vertex has fixed components.
Reimplemented from corbo::VectorVertex.
Definition at line 388 of file vector_vertex.h.
|
inlineoverridevirtual |
Check if individual components are fixed or unfixed.
Reimplemented from corbo::VectorVertex.
Definition at line 390 of file vector_vertex.h.
|
inlineoverridevirtual |
Define the increment for the unfixed components of the vertex: x += inc with dim(inc)=getDimensionUnfixed().
Reimplemented from corbo::VectorVertex.
Definition at line 374 of file vector_vertex.h.
|
inlineoverridevirtual |
Set values and bounds at once.
Reimplemented from corbo::VectorVertex.
Definition at line 327 of file vector_vertex.h.
|
inline |
Set values and bounds at once (overload with fixed vector)
Definition at line 340 of file vector_vertex.h.
|
inlineoverridevirtual |
Change the dimension of the vertex (lower and upper bounds needs to be redefined)
Reimplemented from corbo::VectorVertex.
Definition at line 319 of file vector_vertex.h.
|
inline |
Set component with idx (0 <= idx < dimension()) to (un)fixed.
Definition at line 353 of file vector_vertex.h.
|
inline |
Set logical array [dimension() x 1] in order to fix selected components.
Definition at line 360 of file vector_vertex.h.
|
inlineoverridevirtual |
Set complete vertex to fixed (and hence skip during optimization)
Reimplemented from corbo::VectorVertex.
Definition at line 367 of file vector_vertex.h.
|
protected |
Definition at line 444 of file vector_vertex.h.
|
protected |
Definition at line 445 of file vector_vertex.h.