Public Types | Public Member Functions | Protected Attributes | List of all members
corbo::MixedEdgeGenericVectorFun< VerticesT > Class Template Reference

#include <generic_edge.h>

Inheritance diagram for corbo::MixedEdgeGenericVectorFun< VerticesT >:
Inheritance graph
[legend]

Public Types

using ExtFunT = std::function< void(const VertexContainer &, Eigen::Ref< Eigen::VectorXd >)>
 
using ExtPrecomputeT = std::function< void(const VertexContainer &)>
 
using Ptr = std::shared_ptr< MixedEdgeGenericVectorFun >
 
using UPtr = std::unique_ptr< MixedEdgeGenericVectorFun >
 
- Public Types inherited from corbo::MixedEdge< VerticesT... >
using ConstPtr = std::shared_ptr< const MixedEdge >
 
using Ptr = std::shared_ptr< MixedEdge >
 
using UPtr = std::unique_ptr< MixedEdge >
 
using VertexContainer = std::array< VertexInterface *, numVerticesCompileTime >
 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
 
void computeInequalityValues (Eigen::Ref< Eigen::VectorXd > ineq_values) override
 
void computeObjectiveValues (Eigen::Ref< Eigen::VectorXd > obj_values) override
 
int getEqualityDimension () const override
 
int getInequalityDimension () const override
 
int getObjectiveDimension () const override
 Construct generic vector function edge by passing the dimension D, the function object, a jacobian and all vertices. More...
 
bool isObjectiveLeastSquaresForm () const override
 
 MixedEdgeGenericVectorFun (int obj_dim, int eq_dim, int ineq_dim, const ExtPrecomputeT &precompute_fun, const ExtFunT &obj_fun, const ExtFunT &eq_fun, const ExtFunT &ineq_fun, VerticesT &... vertices)
 Construct generic vector function edge by passing the dimension D, the function object and all vertices. More...
 
void precompute () override
 
void setLinear (bool linear)
 
void setObjectiveLsqForm (bool obj_lsq)
 
- Public Member Functions inherited from corbo::MixedEdge< VerticesT... >
int getNumVertices () const override
 Return number of attached vertices. More...
 
const VertexInterfacegetVertex (int idx) const override
 
VertexInterfacegetVertexRaw (int idx) override
 Get access to vertex with index idx (0 <= idx < numVertices) More...
 
 MixedEdge ()=delete
 
 MixedEdge (VerticesT &... args)
 Construct edge by providing connected vertices. More...
 
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...
 
int getEdgeEqualityIdx () const
 
int getEdgeInequalityIdx () const
 
int getEdgeObjectiveIdx () const
 Retrieve current edge index (warning, this value is determined within the related HyperGraph) More...
 
virtual bool isEqualityLinear () const
 
virtual bool isInequalityLinear () const
 
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
 
- 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

int _eq_dim = 0
 
ExtFunT _eq_fun
 
int _ineq_dim = 0
 
ExtFunT _ineq_fun
 
bool _linear = false
 
int _obj_dim = 0
 
ExtFunT _obj_fun
 Store the external function or functor. More...
 
bool _obj_lsq_form = false
 
ExtPrecomputeT _preqcompute_fun
 
- Protected Attributes inherited from corbo::MixedEdge< VerticesT... >
const VertexContainer _vertices
 Vertex container. More...
 
- Protected Attributes inherited from corbo::BaseMixedEdge
int _edge_idx_eq = 0
 
int _edge_idx_ineq = 0
 
int _edge_idx_obj = 0
 
EdgeCache _equality_cache
 
EdgeCache _inequality_cache
 
EdgeCache _objective_cache
 

Additional Inherited Members

- Static Public Attributes inherited from corbo::MixedEdge< VerticesT... >
static constexpr const int numVerticesCompileTime
 Return number of vertices at compile-time. More...
 

Detailed Description

template<class... VerticesT>
class corbo::MixedEdgeGenericVectorFun< VerticesT >

Definition at line 211 of file generic_edge.h.

Member Typedef Documentation

◆ ExtFunT

template<class... VerticesT>
using corbo::MixedEdgeGenericVectorFun< VerticesT >::ExtFunT = std::function<void(const VertexContainer&, Eigen::Ref<Eigen::VectorXd>)>

Definition at line 225 of file generic_edge.h.

◆ ExtPrecomputeT

template<class... VerticesT>
using corbo::MixedEdgeGenericVectorFun< VerticesT >::ExtPrecomputeT = std::function<void(const VertexContainer&)>

Definition at line 224 of file generic_edge.h.

◆ Ptr

template<class... VerticesT>
using corbo::MixedEdgeGenericVectorFun< VerticesT >::Ptr = std::shared_ptr<MixedEdgeGenericVectorFun>

Definition at line 217 of file generic_edge.h.

◆ UPtr

template<class... VerticesT>
using corbo::MixedEdgeGenericVectorFun< VerticesT >::UPtr = std::unique_ptr<MixedEdgeGenericVectorFun>

Definition at line 218 of file generic_edge.h.

Constructor & Destructor Documentation

◆ MixedEdgeGenericVectorFun()

template<class... VerticesT>
corbo::MixedEdgeGenericVectorFun< VerticesT >::MixedEdgeGenericVectorFun ( int  obj_dim,
int  eq_dim,
int  ineq_dim,
const ExtPrecomputeT precompute_fun,
const ExtFunT obj_fun,
const ExtFunT eq_fun,
const ExtFunT ineq_fun,
VerticesT &...  vertices 
)
inline

Construct generic vector function edge by passing the dimension D, the function object and all vertices.

Definition at line 229 of file generic_edge.h.

Member Function Documentation

◆ computeEqualityValues()

template<class... VerticesT>
void corbo::MixedEdgeGenericVectorFun< VerticesT >::computeEqualityValues ( Eigen::Ref< Eigen::VectorXd >  eq_values)
inlineoverridevirtual

Implements corbo::MixedEdge< VerticesT... >.

Definition at line 262 of file generic_edge.h.

◆ computeInequalityValues()

template<class... VerticesT>
void corbo::MixedEdgeGenericVectorFun< VerticesT >::computeInequalityValues ( Eigen::Ref< Eigen::VectorXd >  ineq_values)
inlineoverridevirtual

Implements corbo::MixedEdge< VerticesT... >.

Definition at line 263 of file generic_edge.h.

◆ computeObjectiveValues()

template<class... VerticesT>
void corbo::MixedEdgeGenericVectorFun< VerticesT >::computeObjectiveValues ( Eigen::Ref< Eigen::VectorXd >  obj_values)
inlineoverridevirtual

Implements corbo::MixedEdge< VerticesT... >.

Definition at line 261 of file generic_edge.h.

◆ getEqualityDimension()

template<class... VerticesT>
int corbo::MixedEdgeGenericVectorFun< VerticesT >::getEqualityDimension ( ) const
inlineoverridevirtual

Implements corbo::MixedEdge< VerticesT... >.

Definition at line 249 of file generic_edge.h.

◆ getInequalityDimension()

template<class... VerticesT>
int corbo::MixedEdgeGenericVectorFun< VerticesT >::getInequalityDimension ( ) const
inlineoverridevirtual

Implements corbo::MixedEdge< VerticesT... >.

Definition at line 250 of file generic_edge.h.

◆ getObjectiveDimension()

template<class... VerticesT>
int corbo::MixedEdgeGenericVectorFun< VerticesT >::getObjectiveDimension ( ) const
inlineoverridevirtual

Construct generic vector function edge by passing the dimension D, the function object, a jacobian and all vertices.

Implements corbo::MixedEdge< VerticesT... >.

Definition at line 248 of file generic_edge.h.

◆ isObjectiveLeastSquaresForm()

template<class... VerticesT>
bool corbo::MixedEdgeGenericVectorFun< VerticesT >::isObjectiveLeastSquaresForm ( ) const
inlineoverridevirtual

Implements corbo::BaseMixedEdge.

Definition at line 255 of file generic_edge.h.

◆ precompute()

template<class... VerticesT>
void corbo::MixedEdgeGenericVectorFun< VerticesT >::precompute ( )
inlineoverridevirtual

Implements corbo::MixedEdge< VerticesT... >.

Definition at line 260 of file generic_edge.h.

◆ setLinear()

template<class... VerticesT>
void corbo::MixedEdgeGenericVectorFun< VerticesT >::setLinear ( bool  linear)
inline

Definition at line 274 of file generic_edge.h.

◆ setObjectiveLsqForm()

template<class... VerticesT>
void corbo::MixedEdgeGenericVectorFun< VerticesT >::setObjectiveLsqForm ( bool  obj_lsq)
inline

Definition at line 276 of file generic_edge.h.

Member Data Documentation

◆ _eq_dim

template<class... VerticesT>
int corbo::MixedEdgeGenericVectorFun< VerticesT >::_eq_dim = 0
protected

Definition at line 287 of file generic_edge.h.

◆ _eq_fun

template<class... VerticesT>
ExtFunT corbo::MixedEdgeGenericVectorFun< VerticesT >::_eq_fun
protected

Definition at line 281 of file generic_edge.h.

◆ _ineq_dim

template<class... VerticesT>
int corbo::MixedEdgeGenericVectorFun< VerticesT >::_ineq_dim = 0
protected

Definition at line 288 of file generic_edge.h.

◆ _ineq_fun

template<class... VerticesT>
ExtFunT corbo::MixedEdgeGenericVectorFun< VerticesT >::_ineq_fun
protected

Definition at line 282 of file generic_edge.h.

◆ _linear

template<class... VerticesT>
bool corbo::MixedEdgeGenericVectorFun< VerticesT >::_linear = false
protected

Definition at line 285 of file generic_edge.h.

◆ _obj_dim

template<class... VerticesT>
int corbo::MixedEdgeGenericVectorFun< VerticesT >::_obj_dim = 0
protected

Definition at line 286 of file generic_edge.h.

◆ _obj_fun

template<class... VerticesT>
ExtFunT corbo::MixedEdgeGenericVectorFun< VerticesT >::_obj_fun
protected

Store the external function or functor.

Definition at line 280 of file generic_edge.h.

◆ _obj_lsq_form

template<class... VerticesT>
bool corbo::MixedEdgeGenericVectorFun< VerticesT >::_obj_lsq_form = false
protected

Definition at line 284 of file generic_edge.h.

◆ _preqcompute_fun

template<class... VerticesT>
ExtPrecomputeT corbo::MixedEdgeGenericVectorFun< VerticesT >::_preqcompute_fun
protected

Definition at line 279 of file generic_edge.h.


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


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03