Public Types | Public Member Functions | Friends | List of all members
corbo::EdgeInterface Class Referenceabstract

Generic interface class for edges. More...

#include <edge_interface.h>

Inheritance diagram for corbo::EdgeInterface:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< EdgeInterface >
 
using UPtr = std::unique_ptr< EdgeInterface >
 

Public Member Functions

virtual double computeSquaredNormOfValues ()
 
virtual double computeSumOfValues ()
 
virtual void computeValues (Eigen::Ref< Eigen::VectorXd > values)=0
 Compute function values. More...
 
virtual int getDimension () const =0
 Get dimension of the edge (dimension of the cost-function/constraint value vector) More...
 
int getNumFiniteVerticesLowerBounds () const
 
int getNumFiniteVerticesUpperBounds () const
 
virtual int getNumVertices () const =0
 Return number of attached vertices. More...
 
virtual const VertexInterfacegetVertex (int idx) const =0
 
virtual VertexInterfacegetVertexRaw (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...
 

Friends

class EdgeSetInterface
 

Detailed Description

Generic interface class for edges.

This abstract class defines the interface for edges for the HyperGraph. Cost functions and constraints (that depend on vertices) are formulated as multi-edges. Multi-edges can connect an arbitary number of vertices. The resulting graph is called hyper-graph. If the number of vertices attached to a single edge is low, the resulting optimization problem is likely to be sparse.

See also
HyperGraph, VertexInterface, BaseEdge
Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)

Definition at line 54 of file edge_interface.h.

Member Typedef Documentation

◆ Ptr

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

Definition at line 59 of file edge_interface.h.

◆ UPtr

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

Definition at line 60 of file edge_interface.h.

Constructor & Destructor Documentation

◆ ~EdgeInterface()

virtual corbo::EdgeInterface::~EdgeInterface ( )
inlinevirtual

Virtual destructor.

Definition at line 63 of file edge_interface.h.

Member Function Documentation

◆ computeSquaredNormOfValues()

virtual double corbo::EdgeInterface::computeSquaredNormOfValues ( )
inlinevirtual

Definition at line 87 of file edge_interface.h.

◆ computeSumOfValues()

virtual double corbo::EdgeInterface::computeSumOfValues ( )
inlinevirtual

Definition at line 80 of file edge_interface.h.

◆ computeValues()

virtual void corbo::EdgeInterface::computeValues ( Eigen::Ref< Eigen::VectorXd >  values)
pure virtual

Compute function values.

Here, the actual cost/constraint function values are computed:

  • objective in non-least-squares form: e(x) (hereby, the actual cost is f(x) = e(x)^T e(x))
  • objective in least-squares form: f(x)
  • equality constraints: ceq(x) (in case constraints are satisfied: ceq(x) = 0)
  • inequality constraints: c(x) (in case constraints are satisfied: c(x) < 0)
    Parameters
    [in]valuesvalues should be stored here according to getDimension().

Implemented in corbo::UncompressedCollocationEdge, corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge, corbo::MSDynamicsOnlyMultiControlsEdge, corbo::CompressedCollocationMultipleControlsEdge, corbo::TernaryVectorScalarVertexEdge< T, ComputeMethod >, corbo::LeftSumInequalityEdge, corbo::BinaryVectorScalarVertexEdge< T, ComputeMethod >, corbo::CompressedCollocationEdge, corbo::BinaryVectorVertexEdge< T, ComputeMethod >, corbo::LeftSumEqualityEdge, corbo::UnaryScalarVertexEdge< T, ComputeMethod >, corbo::LeftSumCostEdge, corbo::UnaryVectorVertexEdge< T, ComputeMethod >, corbo::TrapezoidalCollocationIntegralInequalityEdge, corbo::TrapezoidalIntegralInequalityEdge, corbo::Edge<>, corbo::TrapezoidalCollocationIntegralEqualityEdge, corbo::TrapezoidalIntegralEqualityEdge, corbo::BaseMixedEdge, corbo::Edge< Vertices >, corbo::Edge< VectorVertex, VectorVertex >, corbo::Edge< VerticesT... >, corbo::Edge< VectorVertex >, corbo::Edge< VectorVertex, VectorVertex, VectorVertex >, corbo::Edge< ScalarVertex >, corbo::Edge< VectorVertex, ScalarVertex >, corbo::Edge< VectorVertex, VectorVertex, ScalarVertex >, corbo::Edge< ScalarVertex, ScalarVertex >, corbo::Edge< VectorVertex, VectorVertex, VectorVertex, VectorVertex, ScalarVertex >, corbo::Edge< VectorVertex, VectorVertex, VectorVertex, ScalarVertex >, corbo::Edge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::EdgeGenericVectorFun< D, VerticesT >, corbo::TrapezoidalCollocationIntegralEqualityDynamicsEdge, corbo::TrapezoidalIntegralEqualityDynamicsEdge, corbo::BaseEdge, corbo::TrapezoidalIntegralCostEdge, corbo::MSVariableDynamicsOnlyEdge, corbo::TrapezoidalCollocationIntegralCostEdge, corbo::L1StabInequalityEdge, corbo::EdgeGenericScalarFun< VerticesT >, corbo::QuadratureCollocationDynamicsOnly, corbo::FDCollocationEdge, corbo::MSDynamicsOnlyEdge, corbo::TrapezoidalCollocationDynamicsOnlyEdge, corbo::L1StabCostEdge, and corbo::TwoScalarEqualEdge.

◆ getDimension()

virtual int corbo::EdgeInterface::getDimension ( ) const
pure virtual

Get dimension of the edge (dimension of the cost-function/constraint value vector)

Implemented in corbo::UncompressedCollocationEdge, corbo::MSDynamicsOnlyMultiControlsMultiDtsEdge, corbo::MSDynamicsOnlyMultiControlsEdge, corbo::CompressedCollocationMultipleControlsEdge, corbo::TernaryVectorScalarVertexEdge< T, ComputeMethod >, corbo::LeftSumInequalityEdge, corbo::BinaryVectorScalarVertexEdge< T, ComputeMethod >, corbo::CompressedCollocationEdge, corbo::LeftSumEqualityEdge, corbo::BinaryVectorVertexEdge< T, ComputeMethod >, corbo::UnaryScalarVertexEdge< T, ComputeMethod >, corbo::LeftSumCostEdge, corbo::UnaryVectorVertexEdge< T, ComputeMethod >, corbo::TrapezoidalCollocationIntegralInequalityEdge, corbo::TrapezoidalIntegralInequalityEdge, corbo::Edge<>, corbo::TrapezoidalCollocationIntegralEqualityEdge, corbo::TrapezoidalIntegralEqualityEdge, corbo::BaseMixedEdge, corbo::Edge< Vertices >, corbo::Edge< VectorVertex, VectorVertex >, corbo::Edge< VerticesT... >, corbo::Edge< VectorVertex >, corbo::Edge< VectorVertex, VectorVertex, VectorVertex >, corbo::Edge< ScalarVertex >, corbo::Edge< VectorVertex, ScalarVertex >, corbo::Edge< VectorVertex, VectorVertex, ScalarVertex >, corbo::Edge< ScalarVertex, ScalarVertex >, corbo::Edge< VectorVertex, VectorVertex, VectorVertex, VectorVertex, ScalarVertex >, corbo::Edge< VectorVertex, VectorVertex, VectorVertex, ScalarVertex >, corbo::Edge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >, corbo::EdgeGenericVectorFun< D, VerticesT >, corbo::TrapezoidalCollocationIntegralEqualityDynamicsEdge, corbo::TrapezoidalIntegralEqualityDynamicsEdge, corbo::TrapezoidalIntegralCostEdge, corbo::BaseEdge, corbo::TrapezoidalCollocationIntegralCostEdge, corbo::MSVariableDynamicsOnlyEdge, corbo::L1StabInequalityEdge, corbo::EdgeGenericScalarFun< VerticesT >, corbo::QuadratureCollocationDynamicsOnly, corbo::FDCollocationEdge, corbo::MSDynamicsOnlyEdge, corbo::TrapezoidalCollocationDynamicsOnlyEdge, corbo::L1StabCostEdge, and corbo::TwoScalarEqualEdge.

◆ getNumFiniteVerticesLowerBounds()

int corbo::EdgeInterface::getNumFiniteVerticesLowerBounds ( ) const

Definition at line 34 of file edge_interface.cpp.

◆ getNumFiniteVerticesUpperBounds()

int corbo::EdgeInterface::getNumFiniteVerticesUpperBounds ( ) const

Definition at line 44 of file edge_interface.cpp.

◆ getNumVertices()

virtual int corbo::EdgeInterface::getNumVertices ( ) const
pure virtual

◆ getVertex()

virtual const VertexInterface* corbo::EdgeInterface::getVertex ( int  idx) const
pure virtual

◆ getVertexRaw()

virtual VertexInterface* corbo::EdgeInterface::getVertexRaw ( int  idx)
pure virtual

◆ verticesDimension()

virtual int corbo::EdgeInterface::verticesDimension ( ) const
pure virtual

Friends And Related Function Documentation

◆ EdgeSetInterface

friend class EdgeSetInterface
friend

Definition at line 56 of file edge_interface.h.


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


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