|
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 VertexInterface * | getVertex (int idx) const override |
|
VertexInterface * | getVertexRaw (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...
|
|
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...
|
|
EdgeCache & | getCache () |
| Retreive values computed previously via computeValuesCached() More...
|
|
const EdgeCache & | getCache () const |
|
virtual double | computeSquaredNormOfValues () |
|
virtual double | computeSumOfValues () |
|
int | getNumFiniteVerticesLowerBounds () const |
|
int | getNumFiniteVerticesUpperBounds () const |
|
virtual | ~EdgeInterface () |
| Virtual destructor. More...
|
|
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
-
D | Dimension 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
-
D | Dimension of the edge (value vector). |
Definition at line 148 of file edge.h.
template<class... Vertices>
template<class... VerticesT>
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.
template<class... Vertices>
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
-
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.