Public Types | Public Member Functions | Protected Attributes | List of all members
corbo::MixedEdge<> Class Referenceabstract

#include <edge.h>

Inheritance diagram for corbo::MixedEdge<>:
Inheritance graph
[legend]

Public Types

using ConstPtr = std::shared_ptr< const MixedEdge >
 
using Ptr = std::shared_ptr< MixedEdge >
 
using UPtr = std::unique_ptr< MixedEdge >
 
using VertexContainer = std::vector< VertexInterface * >
 Typedef to represent the vertex container. More...
 
- Public Types inherited from corbo::BaseMixedEdge
using Ptr = std::shared_ptr< BaseMixedEdge >
 
using UPtr = std::unique_ptr< BaseMixedEdge >
 
- Public Types inherited from corbo::EdgeInterface
using Ptr = std::shared_ptr< EdgeInterface >
 
using UPtr = std::unique_ptr< EdgeInterface >
 

Public Member Functions

void computeEqualityValues (Eigen::Ref< Eigen::VectorXd > eq_values) override=0
 
void computeInequalityValues (Eigen::Ref< Eigen::VectorXd > ineq_values) override=0
 
void computeObjectiveValues (Eigen::Ref< Eigen::VectorXd > obj_values) override=0
 
int getEqualityDimension () const override=0
 
int getInequalityDimension () const override=0
 
int getNumVertices () const override
 Return number of attached vertices. More...
 
int getObjectiveDimension () const override=0
 
const VertexInterfacegetVertex (int idx) const override
 
VertexInterfacegetVertexRaw (int idx) override
 Get access to vertex with index idx (0 <= idx < numVertices) More...
 
 MixedEdge ()
 
 MixedEdge (int num_vertices)
 
void precompute () override=0
 
void resizeVertexContainer (int n)
 Set number n of vertices attached to this edge. More...
 
void setVertex (int idx, VertexInterface &vertex)
 
int verticesDimension () const override
 Return the combined dimension of all attached vertices (excluding fixed vertex components) More...
 
- Public Member Functions inherited from corbo::BaseMixedEdge
virtual void computeConstraintHessians (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &eq_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &ineq_jacobian_i, Eigen::Ref< Eigen::MatrixXd > eq_hessian_ij, Eigen::Ref< Eigen::MatrixXd > ineq_hessian_ij, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr)
 
virtual void computeConstraintHessiansInc (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &eq_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &ineq_jacobian_i, Eigen::Ref< Eigen::MatrixXd > eq_hessian_ij, Eigen::Ref< Eigen::MatrixXd > ineq_hessian_ij, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr)
 
virtual void computeConstraintJacobians (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > eq_jacobian, Eigen::Ref< Eigen::MatrixXd > ineq_jacobian, const double *eq_multipliers=nullptr, const double *ineq_multipliers=nullptr)
 
virtual void computeEqualityHessian (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &block_jacobian_i, Eigen::Ref< Eigen::MatrixXd > block_hessian_ij, const double *multipliers=nullptr, double weight=1.0)
 
virtual void computeEqualityHessianInc (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &block_jacobian_i, Eigen::Ref< Eigen::MatrixXd > block_hessian_ij, const double *multipliers=nullptr, double weight=1.0)
 
virtual void computeEqualityJacobian (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr)
 
virtual void computeHessians (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &obj_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &eq_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &ineq_jacobian_i, Eigen::Ref< Eigen::MatrixXd > obj_hessian_ij, Eigen::Ref< Eigen::MatrixXd > eq_hessian_ij, Eigen::Ref< Eigen::MatrixXd > ineq_hessian_ij, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr, double weight_obj=1.0)
 
virtual void computeHessiansInc (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &obj_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &eq_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &ineq_jacobian_i, Eigen::Ref< Eigen::MatrixXd > obj_hessian_ij, Eigen::Ref< Eigen::MatrixXd > eq_hessian_ij, Eigen::Ref< Eigen::MatrixXd > ineq_hessian_ij, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr, double weight_obj=1.0)
 
virtual void computeInequalityHessian (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &block_jacobian_i, Eigen::Ref< Eigen::MatrixXd > block_hessian_ij, const double *multipliers=nullptr, double weight=1.0)
 
virtual void computeInequalityHessianInc (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &block_jacobian_i, Eigen::Ref< Eigen::MatrixXd > block_hessian_ij, const double *multipliers=nullptr, double weight=1.0)
 
virtual void computeInequalityJacobian (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr)
 
virtual void computeJacobians (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > obj_jacobian, Eigen::Ref< Eigen::MatrixXd > eq_jacobian, Eigen::Ref< Eigen::MatrixXd > ineq_jacobian, const double *obj_multipliers=nullptr, const double *eq_multipliers=nullptr, const double *ineq_multipliers=nullptr)
 
virtual void computeObjectiveHessian (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &block_jacobian_i, Eigen::Ref< Eigen::MatrixXd > block_hessian_ij, const double *multipliers=nullptr, double weight=1.0)
 
virtual void computeObjectiveHessianInc (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &block_jacobian_i, Eigen::Ref< Eigen::MatrixXd > block_hessian_ij, const double *multipliers=nullptr, double weight=1.0)
 
virtual void computeObjectiveJacobian (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr)
 
virtual double computeSquaredNormOfObjectiveValues ()
 
virtual double computeSumOfObjectiveValues ()
 
void computeValues (Eigen::Ref< Eigen::VectorXd > values) final
 Compute function values. More...
 
int getDimension () const override
 Get dimension of the edge (dimension of the cost-function/constraint value vector) More...
 
virtual bool isEqualityLinear () const
 
virtual bool isInequalityLinear () const
 
virtual bool isObjectiveLeastSquaresForm () const =0
 
virtual bool isObjectiveLinear () const
 Return true if the edge is linear (and hence its Hessian is always zero) More...
 
void reserveCacheMemory (int num_value_vectors, int num_jacobians)
 
void reserveValuesCacheMemory (int num_obj_values, int num_eq_values, int num_ineq_values)
 
void reserveJacobiansCacheMemory (int num_obj_jacobians, int num_eq_jacobians, int num_ineq_jacobians)
 
void computeObjectiveValuesCached ()
 Call computeObjectiveValues() and store result to the internal cache. More...
 
void computeSquaredNormOfObjectiveValuesCached ()
 compute the specialied squared-norm method for computing the values (note only the first element in the values cache is used) More...
 
void computeEqualityValuesCached ()
 Call computeEqualityValues() and store result to the internal cache. More...
 
void computeInequalityValuesCached ()
 Call computeInequalityValues() and store result to the internal cache. More...
 
EdgeCachegetObjectiveCache ()
 
const EdgeCachegetObjectiveCache () const
 
EdgeCachegetEqualityCache ()
 
const EdgeCachegetEqualityCache () const
 
EdgeCachegetInequalityCache ()
 
const EdgeCachegetInequalityCache () const
 
int getEdgeObjectiveIdx () const
 Retrieve current edge index (warning, this value is determined within the related HyperGraph) More...
 
int getEdgeEqualityIdx () const
 
int getEdgeInequalityIdx () const
 
- Public Member Functions inherited from corbo::EdgeInterface
virtual double computeSquaredNormOfValues ()
 
virtual double computeSumOfValues ()
 
int getNumFiniteVerticesLowerBounds () const
 
int getNumFiniteVerticesUpperBounds () const
 
virtual ~EdgeInterface ()
 Virtual destructor. More...
 

Protected Attributes

VertexContainer _vertices
 Vertex container. More...
 
- Protected Attributes inherited from corbo::BaseMixedEdge
int _edge_idx_obj = 0
 
int _edge_idx_eq = 0
 
int _edge_idx_ineq = 0
 
EdgeCache _objective_cache
 
EdgeCache _equality_cache
 
EdgeCache _inequality_cache
 

Detailed Description

Definition at line 390 of file edge.h.

Member Typedef Documentation

◆ ConstPtr

using corbo::MixedEdge<>::ConstPtr = std::shared_ptr<const MixedEdge>

Definition at line 394 of file edge.h.

◆ Ptr

using corbo::MixedEdge<>::Ptr = std::shared_ptr<MixedEdge>

Definition at line 393 of file edge.h.

◆ UPtr

using corbo::MixedEdge<>::UPtr = std::unique_ptr<MixedEdge>

Definition at line 395 of file edge.h.

◆ VertexContainer

Typedef to represent the vertex container.

Definition at line 398 of file edge.h.

Constructor & Destructor Documentation

◆ MixedEdge() [1/2]

corbo::MixedEdge<>::MixedEdge ( )
inline

Definition at line 401 of file edge.h.

◆ MixedEdge() [2/2]

corbo::MixedEdge<>::MixedEdge ( int  num_vertices)
inlineexplicit

Definition at line 403 of file edge.h.

Member Function Documentation

◆ computeEqualityValues()

void corbo::MixedEdge<>::computeEqualityValues ( Eigen::Ref< Eigen::VectorXd >  eq_values)
overridepure virtual

◆ computeInequalityValues()

void corbo::MixedEdge<>::computeInequalityValues ( Eigen::Ref< Eigen::VectorXd >  ineq_values)
overridepure virtual

◆ computeObjectiveValues()

void corbo::MixedEdge<>::computeObjectiveValues ( Eigen::Ref< Eigen::VectorXd >  obj_values)
overridepure virtual

◆ getEqualityDimension()

int corbo::MixedEdge<>::getEqualityDimension ( ) const
overridepure virtual

◆ getInequalityDimension()

int corbo::MixedEdge<>::getInequalityDimension ( ) const
overridepure virtual

◆ getNumVertices()

int corbo::MixedEdge<>::getNumVertices ( ) const
inlineoverridevirtual

Return number of attached vertices.

Implements corbo::EdgeInterface.

Definition at line 421 of file edge.h.

◆ getObjectiveDimension()

int corbo::MixedEdge<>::getObjectiveDimension ( ) const
overridepure virtual

◆ getVertex()

const VertexInterface* corbo::MixedEdge<>::getVertex ( int  idx) const
inlineoverridevirtual

Implements corbo::EdgeInterface.

Definition at line 450 of file edge.h.

◆ getVertexRaw()

VertexInterface* corbo::MixedEdge<>::getVertexRaw ( int  idx)
inlineoverridevirtual

Get access to vertex with index idx (0 <= idx < numVertices)

Implements corbo::EdgeInterface.

Definition at line 443 of file edge.h.

◆ precompute()

void corbo::MixedEdge<>::precompute ( )
overridepure virtual

◆ resizeVertexContainer()

void corbo::MixedEdge<>::resizeVertexContainer ( int  n)
inline

Set number n of vertices attached to this edge.

Definition at line 406 of file edge.h.

◆ setVertex()

void corbo::MixedEdge<>::setVertex ( int  idx,
VertexInterface vertex 
)
inline

Definition at line 408 of file edge.h.

◆ verticesDimension()

int corbo::MixedEdge<>::verticesDimension ( ) const
inlineoverridevirtual

Return the combined dimension of all attached vertices (excluding fixed vertex components)

Implements corbo::EdgeInterface.

Definition at line 424 of file edge.h.

Member Data Documentation

◆ _vertices

VertexContainer corbo::MixedEdge<>::_vertices
protected

Vertex container.

Definition at line 457 of file edge.h.


The documentation for this class was generated from the following file:


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:07:20