#include <edge_interface.h>
Public Types | |
using | Ptr = std::shared_ptr< BaseMixedEdge > |
using | UPtr = std::unique_ptr< BaseMixedEdge > |
![]() | |
using | Ptr = std::shared_ptr< EdgeInterface > |
using | UPtr = std::unique_ptr< EdgeInterface > |
Public Member Functions | |
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 | computeEqualityValues (Eigen::Ref< Eigen::VectorXd > eq_values)=0 |
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 | computeInequalityValues (Eigen::Ref< Eigen::VectorXd > ineq_values)=0 |
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 void | computeObjectiveValues (Eigen::Ref< Eigen::VectorXd > obj_values)=0 |
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 int | getEqualityDimension () const =0 |
virtual int | getInequalityDimension () const =0 |
virtual int | getObjectiveDimension () const =0 |
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... | |
virtual void | precompute ()=0 |
Caching of edge values and block jacobians | |
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... | |
EdgeCache & | getObjectiveCache () |
const EdgeCache & | getObjectiveCache () const |
EdgeCache & | getEqualityCache () |
const EdgeCache & | getEqualityCache () const |
EdgeCache & | getInequalityCache () |
const EdgeCache & | getInequalityCache () const |
![]() | |
virtual double | computeSquaredNormOfValues () |
virtual double | computeSumOfValues () |
int | getNumFiniteVerticesLowerBounds () const |
int | getNumFiniteVerticesUpperBounds () const |
virtual int | getNumVertices () const =0 |
Return number of attached vertices. More... | |
virtual const VertexInterface * | getVertex (int idx) const =0 |
virtual VertexInterface * | getVertexRaw (int idx)=0 |
Get access to vertex with index idx (0 <= idx < numVertices) More... | |
virtual int | verticesDimension () const =0 |
Return the combined dimension of all attached vertices (excluding fixed vertex components) More... | |
virtual | ~EdgeInterface () |
Virtual destructor. More... | |
Protected Attributes | |
int | _edge_idx_eq = 0 |
int | _edge_idx_ineq = 0 |
int | _edge_idx_obj = 0 |
EdgeCache | _equality_cache |
EdgeCache | _inequality_cache |
EdgeCache | _objective_cache |
Friends | |
class | EdgeSetInterface |
Definition at line 217 of file edge_interface.h.
using corbo::BaseMixedEdge::Ptr = std::shared_ptr<BaseMixedEdge> |
Definition at line 222 of file edge_interface.h.
using corbo::BaseMixedEdge::UPtr = std::unique_ptr<BaseMixedEdge> |
Definition at line 223 of file edge_interface.h.
|
virtual |
Definition at line 781 of file edge_interface.cpp.
|
virtual |
Definition at line 1105 of file edge_interface.cpp.
|
virtual |
Definition at line 466 of file edge_interface.cpp.
|
virtual |
Definition at line 580 of file edge_interface.cpp.
|
virtual |
Definition at line 913 of file edge_interface.cpp.
|
virtual |
Definition at line 305 of file edge_interface.cpp.
|
pure virtual |
Implemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MixedEdge<>, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::MixedEdge< Vertices >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex >, corbo::MixedEdge< VerticesT... >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::MixedEdgeGenericVectorFun< VerticesT >, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
|
inline |
Call computeEqualityValues() and store result to the internal cache.
Definition at line 332 of file edge_interface.h.
|
virtual |
Definition at line 690 of file edge_interface.cpp.
|
virtual |
Definition at line 1019 of file edge_interface.cpp.
|
virtual |
Definition at line 635 of file edge_interface.cpp.
|
virtual |
Definition at line 966 of file edge_interface.cpp.
|
virtual |
Definition at line 349 of file edge_interface.cpp.
|
pure virtual |
Implemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MixedEdge<>, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::MixedEdge< Vertices >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex >, corbo::MixedEdge< VerticesT... >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::MixedEdgeGenericVectorFun< VerticesT >, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
|
inline |
Call computeInequalityValues() and store result to the internal cache.
Definition at line 334 of file edge_interface.h.
|
virtual |
Definition at line 394 of file edge_interface.cpp.
|
virtual |
Definition at line 525 of file edge_interface.cpp.
|
virtual |
Definition at line 860 of file edge_interface.cpp.
|
virtual |
Definition at line 261 of file edge_interface.cpp.
|
pure virtual |
Implemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MixedEdge<>, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::MixedEdge< Vertices >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex >, corbo::MixedEdge< VerticesT... >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::MixedEdgeGenericVectorFun< VerticesT >, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
|
inline |
Call computeObjectiveValues() and store result to the internal cache.
Definition at line 328 of file edge_interface.h.
|
inlinevirtual |
Definition at line 258 of file edge_interface.h.
|
inline |
compute the specialied squared-norm method for computing the values (note only the first element in the values cache is used)
Definition at line 330 of file edge_interface.h.
|
inlinevirtual |
Definition at line 251 of file edge_interface.h.
|
inlinefinalvirtual |
Compute function values.
Here, the actual cost/constraint function values are computed:
[in] | values | values should be stored here according to getDimension(). |
Implements corbo::EdgeInterface.
Definition at line 243 of file edge_interface.h.
|
inlineoverridevirtual |
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Implements corbo::EdgeInterface.
Definition at line 225 of file edge_interface.h.
|
inline |
Definition at line 349 of file edge_interface.h.
|
inline |
Definition at line 350 of file edge_interface.h.
|
inline |
Retrieve current edge index (warning, this value is determined within the related HyperGraph)
Definition at line 348 of file edge_interface.h.
|
inline |
Definition at line 339 of file edge_interface.h.
|
inline |
Definition at line 340 of file edge_interface.h.
|
pure virtual |
Implemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::MixedEdge<>, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::MixedEdge< Vertices >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex >, corbo::MixedEdge< VerticesT... >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::MixedEdgeGenericVectorFun< VerticesT >, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
|
inline |
Definition at line 342 of file edge_interface.h.
|
inline |
Definition at line 343 of file edge_interface.h.
|
pure virtual |
Implemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::MixedEdge<>, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::MixedEdge< Vertices >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex >, corbo::MixedEdge< VerticesT... >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::MixedEdgeGenericVectorFun< VerticesT >, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
|
inline |
Definition at line 336 of file edge_interface.h.
|
inline |
Definition at line 337 of file edge_interface.h.
|
pure virtual |
Implemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::MixedEdge<>, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::MixedEdge< Vertices >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex >, corbo::MixedEdge< VerticesT... >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::MixedEdgeGenericVectorFun< VerticesT >, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
|
inlinevirtual |
Reimplemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
Definition at line 235 of file edge_interface.h.
|
inlinevirtual |
Reimplemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
Definition at line 236 of file edge_interface.h.
|
pure virtual |
Implemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::MixedEdgeGenericVectorFun< VerticesT >, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
|
inlinevirtual |
Return true if the edge is linear (and hence its Hessian is always zero)
Reimplemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
Definition at line 234 of file edge_interface.h.
|
pure virtual |
Implemented in corbo::CombinedUncompressedCollocationEdge, corbo::CombinedCompressedCollocationMultipleControlsEdge, corbo::CombinedCompressedCollocationEdge, corbo::ConstControlCombinedCompressedCollocationEdge, corbo::MultipleShootingEdge, corbo::MixedEdge<>, corbo::MultipleShootingEdgeSingleControlTimeScaling, corbo::MixedEdge< Vertices >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex >, corbo::MixedEdge< VerticesT... >, corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::MixedEdgeGenericVectorFun< VerticesT >, corbo::QuadratureCollocationEdge, and corbo::MultipleShootingEdgeSingleControl.
Definition at line 309 of file edge_interface.h.
|
inline |
Definition at line 320 of file edge_interface.h.
|
inline |
Definition at line 314 of file edge_interface.h.
|
friend |
Definition at line 219 of file edge_interface.h.
|
protected |
Definition at line 354 of file edge_interface.h.
|
protected |
Definition at line 355 of file edge_interface.h.
|
protected |
Definition at line 353 of file edge_interface.h.
|
protected |
Definition at line 358 of file edge_interface.h.
|
protected |
Definition at line 359 of file edge_interface.h.
|
protected |
Definition at line 357 of file edge_interface.h.