Public Types | Public Member Functions | Static Public Attributes | Protected Attributes | List of all members
corbo::Edge< Vertices > Class Template Referenceabstract

Templated base edge class that stores an arbitary number of value. More...

#include <edge.h>

Inheritance diagram for corbo::Edge< Vertices >:
Inheritance graph
[legend]

Public Types

using ConstPtr = std::shared_ptr< const Edge >
 
using Ptr = std::shared_ptr< Edge >
 
using UPtr = std::unique_ptr< Edge >
 
using VertexContainer = std::array< VertexInterface *, numVerticesCompileTime >
 Typedef to represent the vertex container. More...
 
- Public Types inherited from corbo::BaseEdge
using Ptr = std::shared_ptr< BaseEdge >
 
using UPtr = std::unique_ptr< BaseEdge >
 
- Public Types inherited from corbo::EdgeInterface
using Ptr = std::shared_ptr< EdgeInterface >
 
using UPtr = std::unique_ptr< EdgeInterface >
 

Public Member Functions

void computeValues (Eigen::Ref< Eigen::VectorXd > values) override=0
 Compute function values. More...
 
 Edge ()=delete
 
template<class... VerticesT>
 Edge (VerticesT &... args)
 Construct edge by providing connected vertices. More...
 
int getDimension () const override=0
 Get dimension of the edge (dimension of the cost-function/constraint value vector) More...
 
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...
 
bool isLinear () const override=0
 Return true if the edge is linear (and hence its Hessian is always zero) More...
 
bool providesJacobian () const override
 Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten) More...
 
int verticesDimension () const override
 Return the combined dimension of all attached vertices (excluding fixed vertex components) More...
 
- Public Member Functions inherited from corbo::BaseEdge
virtual void computeHessian (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 computeHessianInc (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)
 Compute edge block Hessian for a given vertex pair. More...
 
virtual void computeHessianInc (int vtx_idx_i, int vtx_idx_j, Eigen::Ref< Eigen::MatrixXd > block_hessian_ij, const double *multipliers=nullptr, double weight=1.0)
 
virtual void computeJacobian (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr)
 Compute edge block jacobian for a given vertex. More...
 
int getEdgeIdx () const
 Retrieve current edge index (warning, this value is determined within the related HyperGraph) More...
 
virtual bool isLeastSquaresForm () const
 Defines if the edge is formulated as Least-Squares form. More...
 
virtual bool providesHessian () const
 Return true if a custom Hessian is provided (e.g. computeHessian() is overwritten) More...
 
void reserveCacheMemory (int num_value_vectors, int num_jacobians)
 
void reserveValuesCacheMemory (int num_value_vectors)
 
void reserveJacobiansCacheMemory (int num_jacobians)
 
void computeValuesCached ()
 Call computeValues() and store result to previously allocated internal cache (call allocateInteralValuesCache() first once) More...
 
void computeSquaredNormOfValuesCached ()
 compute the specialied squared-norm method for computing the values (note only the first element in the values cache is used) More...
 
EdgeCachegetCache ()
 Retreive values computed previously via computeValuesCached() More...
 
const EdgeCachegetCache () 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...
 

Static Public Attributes

static constexpr const int numVerticesCompileTime = sizeof...(Vertices)
 Return number of vertices at compile-time. More...
 

Protected Attributes

const VertexContainer _vertices
 Vertex container. More...
 
- Protected Attributes inherited from corbo::BaseEdge
EdgeCache _cache
 
int _edge_idx = 0
 

Detailed Description

template<class... Vertices>
class corbo::Edge< Vertices >

Templated base edge class that stores an arbitary number of value.

The value dimension is specified statically via a template parameter. The dimension has to be known at compile time and is set by the template parameter D.

Connected vertex types are defined with a number of class templates (Vertices...). Internally, those vertices are stored according to their order of appearence in a vertex container _vertices.

Consequently, in the computeValues() method, vertices can be accessed by _vertices[idx] and statically casted to their particular type if necessary.

Warning
Vertices must remain valid as long as the Edge is in use!
See also
EdgeInterface
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)
Template Parameters
DDimension of the edge (value vector).
Vertices...An arbitary number of vertex types that are attached to this edge Construct edge by providing connected vertices

The order must match the order of template arguments provided to the class.

Warning
Vertices must remain valid as long as the Edge is in use! Templated base edge class that stores an arbitary number of value

Template specialization for edges with a dynamic value dimension. Refer to the description of the non-specialized class.

Warning
Vertices must remain valid as long as the Edge is in use!
See also
EdgeInterface
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)
Template Parameters
DDimension of the edge (value vector).

Definition at line 148 of file edge.h.

Member Typedef Documentation

◆ ConstPtr

template<class... Vertices>
using corbo::Edge< Vertices >::ConstPtr = std::shared_ptr<const Edge>

Definition at line 152 of file edge.h.

◆ Ptr

template<class... Vertices>
using corbo::Edge< Vertices >::Ptr = std::shared_ptr<Edge>

Definition at line 151 of file edge.h.

◆ UPtr

template<class... Vertices>
using corbo::Edge< Vertices >::UPtr = std::unique_ptr<Edge>

Definition at line 153 of file edge.h.

◆ VertexContainer

template<class... Vertices>
using corbo::Edge< Vertices >::VertexContainer = std::array<VertexInterface*, numVerticesCompileTime>

Typedef to represent the vertex container.

Definition at line 159 of file edge.h.

Constructor & Destructor Documentation

◆ Edge() [1/2]

template<class... Vertices>
corbo::Edge< Vertices >::Edge ( )
delete

◆ Edge() [2/2]

template<class... Vertices>
template<class... VerticesT>
corbo::Edge< Vertices >::Edge ( VerticesT &...  args)
inlineexplicit

Construct edge by providing connected vertices.

The order must match the order of template arguments provided to the class.

Warning
Vertices must remain valid as long as the Edge is in use!Construct edge by passing all vertices references.

Definition at line 171 of file edge.h.

Member Function Documentation

◆ computeValues()

template<class... Vertices>
void corbo::Edge< Vertices >::computeValues ( Eigen::Ref< Eigen::VectorXd >  values)
overridepure 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().

Implements corbo::BaseEdge.

Implemented in 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::TrapezoidalCollocationIntegralEqualityEdge, corbo::TrapezoidalIntegralEqualityEdge, corbo::EdgeGenericVectorFun< D, VerticesT >, corbo::TrapezoidalCollocationIntegralEqualityDynamicsEdge, corbo::TrapezoidalIntegralEqualityDynamicsEdge, corbo::TrapezoidalIntegralCostEdge, corbo::MSVariableDynamicsOnlyEdge, corbo::TrapezoidalCollocationIntegralCostEdge, corbo::L1StabInequalityEdge, corbo::EdgeGenericScalarFun< VerticesT >, corbo::FDCollocationEdge, corbo::MSDynamicsOnlyEdge, corbo::TrapezoidalCollocationDynamicsOnlyEdge, corbo::L1StabCostEdge, and corbo::TwoScalarEqualEdge.

◆ getDimension()

template<class... Vertices>
int corbo::Edge< Vertices >::getDimension ( ) const
overridepure virtual

◆ getNumVertices()

template<class... Vertices>
int corbo::Edge< Vertices >::getNumVertices ( ) const
inlineoverridevirtual

Return number of attached vertices.

Implements corbo::EdgeInterface.

Definition at line 181 of file edge.h.

◆ getVertex()

template<class... Vertices>
const VertexInterface* corbo::Edge< Vertices >::getVertex ( int  idx) const
inlineoverridevirtual

Implements corbo::EdgeInterface.

Definition at line 207 of file edge.h.

◆ getVertexRaw()

template<class... Vertices>
VertexInterface* corbo::Edge< Vertices >::getVertexRaw ( int  idx)
inlineoverridevirtual

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

Implements corbo::EdgeInterface.

Definition at line 200 of file edge.h.

◆ isLinear()

template<class... Vertices>
bool corbo::Edge< Vertices >::isLinear ( ) const
overridepure virtual

◆ providesJacobian()

template<class... Vertices>
bool corbo::Edge< Vertices >::providesJacobian ( ) const
inlineoverridevirtual

Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)

Reimplemented from corbo::BaseEdge.

Definition at line 194 of file edge.h.

◆ verticesDimension()

template<class... Vertices>
int corbo::Edge< Vertices >::verticesDimension ( ) const
inlineoverridevirtual

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

Implements corbo::EdgeInterface.

Definition at line 184 of file edge.h.

Member Data Documentation

◆ _vertices

template<class... Vertices>
const VertexContainer corbo::Edge< Vertices >::_vertices
protected

Vertex container.

Definition at line 214 of file edge.h.

◆ numVerticesCompileTime

template<class... Vertices>
constexpr const int corbo::Edge< Vertices >::numVerticesCompileTime = sizeof...(Vertices)
static

Return number of vertices at compile-time.

Definition at line 156 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 Mon Feb 28 2022 22:08:02