Go to the documentation of this file.
25 #ifndef SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_GENERIC_EDGE_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_GENERIC_EDGE_H_
67 template <
class... VerticesT>
68 class EdgeGenericScalarFun :
public Edge<VerticesT...>
79 using Ptr = std::shared_ptr<EdgeGenericScalarFun>;
80 using UPtr = std::unique_ptr<EdgeGenericScalarFun>;
96 bool isLinear()
const override {
return false; }
149 template <
int D,
class... VerticesT>
156 using Ptr = std::shared_ptr<EdgeGenericVectorFun>;
157 using UPtr = std::unique_ptr<EdgeGenericVectorFun>;
180 bool isLinear()
const override {
return false; }
210 template <
class... VerticesT>
217 using Ptr = std::shared_ptr<MixedEdgeGenericVectorFun>;
218 using UPtr = std::unique_ptr<MixedEdgeGenericVectorFun>;
230 const ExtFunT& eq_fun,
const ExtFunT& ineq_fun, VerticesT&... vertices)
294 template <
typename T,
void (T::*ComputeMethod)(
int, const Eigen::Ref<const Eigen::VectorXd>&, Eigen::Ref<Eigen::VectorXd>) const>
298 using Ptr = std::shared_ptr<UnaryVectorVertexEdge>;
332 template <
typename T,
void (T::*ComputeMethod)(
int,
double, Eigen::Ref<Eigen::VectorXd>) const>
336 using Ptr = std::shared_ptr<UnaryScalarVertexEdge>;
370 template <
typename T,
void (T::*ComputeMethod)(
int, const Eigen::Ref<const Eigen::VectorXd>&, const Eigen::Ref<const Eigen::VectorXd>&,
371 Eigen::Ref<Eigen::VectorXd>) const>
375 using Ptr = std::shared_ptr<BinaryVectorVertexEdge>;
410 template <
typename T,
void (T::*ComputeMethod)(
int, const Eigen::Ref<const Eigen::VectorXd>&,
double, Eigen::Ref<Eigen::VectorXd>) const>
414 using Ptr = std::shared_ptr<BinaryVectorScalarVertexEdge>;
449 template <
typename T,
void (T::*ComputeMethod)(
int, const Eigen::Ref<const Eigen::VectorXd>&, const Eigen::Ref<const Eigen::VectorXd>&,
double,
450 Eigen::Ref<Eigen::VectorXd>) const>
454 using Ptr = std::shared_ptr<TernaryVectorScalarVertexEdge>;
457 bool is_linear,
bool is_lsq)
498 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_GENERIC_EDGE_H_
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
std::shared_ptr< EdgeInterface > Ptr
void setLinear(bool linear)
void setLinear(bool linear)
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
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 vertic...
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
UnaryScalarVertexEdge(int dim, int k, const T &fun_obj, ScalarVertex &vertex, bool is_linear, bool is_lsq)
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
std::array< VertexInterface *, numVerticesCompileTime > VertexContainer
Typedef to represent the vertex container.
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
bool isObjectiveLeastSquaresForm() const override
void setLinear(bool linear)
std::shared_ptr< EdgeGenericScalarFun > Ptr
EdgeGenericVectorFun(const ExtFunT &fun, bool lsq_form, VerticesT &... vertices)
Construct generic vector function edge by passing the dimension D, the function object and all vertic...
void precompute() override
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
void computeJacobian(int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multiplier) override
Compute edge block jacobian for a given vertex.
std::array< VertexInterface *, numVerticesCompileTime > VertexContainer
Typedef to represent the vertex container.
std::function< void(const VertexContainer &, int, Eigen::Ref< Eigen::MatrixXd >, const double *)> ExtJacobT
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Eigen::Matrix< double, D, 1 > ErrorVector
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
void setObjectiveLsqForm(bool obj_lsq)
BinaryVectorScalarVertexEdge(int dim, int k, const T &fun_obj, VectorVertex &vertex1, ScalarVertex &vertex2, bool is_linear, bool is_lsq)
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
const VertexContainer _vertices
Vertex container.
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
ExtFunT _fun
Store the external function or functor.
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
std::function< void(const VertexContainer &, Eigen::Ref< Eigen::VectorXd >)> ExtFunT
const Eigen::VectorXd & values() const
Read-access to the underlying value vector.
ExtFunT _fun
Store the external function or functor.
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
std::function< double(const VertexContainer &)> ExtFunT
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
ExtFunT _obj_fun
Store the external function or functor.
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
UnaryVectorVertexEdge(int dim, int k, const T &fun_obj, VectorVertex &vertex, bool is_linear=false, bool is_lsq=false)
BinaryVectorVertexEdge(int dim, int k, const T &fun_obj, VectorVertex &vertex1, VectorVertex &vertex2, bool is_linear, bool is_lsq)
std::function< void(const VertexContainer &, Eigen::Ref< ErrorVector >)> ExtFunT
EdgeGenericScalarFun(const ExtFunT &fun, bool lsq_form, VerticesT &... vertices)
Construct generic scalar function edge by passing the function object and all vertices.
Generic edge for functions .
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
void computeJacobian(int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multiplier=nullptr) override
Compute edge block jacobian for a given vertex.
std::unique_ptr< EdgeInterface > UPtr
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
std::function< void(const VertexContainer &, int, Eigen::Ref< Eigen::MatrixXd >, const double *)> ExtJacobT
A matrix or vector expression mapping an existing expression.
TernaryVectorScalarVertexEdge(int dim, int k, const T &fun_obj, VectorVertex &vec_vtx1, VectorVertex &vec_vtx2, ScalarVertex &scalar_vtx, bool is_linear, bool is_lsq)
const double & value() const
Get underlying value.
virtual void computeJacobian(int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr)
Compute edge block jacobian for a given vertex.
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Vertex implementation for scalar values.
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
std::function< void(const VertexContainer &)> ExtPrecomputeT
ExtPrecomputeT _preqcompute_fun
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
The matrix class, also used for vectors and row-vectors.
Templated base edge class that stores an arbitary number of value.
int getObjectiveDimension() const override
Construct generic vector function edge by passing the dimension D, the function object,...
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
int getEqualityDimension() const override
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
int getInequalityDimension() const override
Vertex implementation that stores an Eigen::VectorXd (dynamic dimension)
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
std::unique_ptr< EdgeGenericScalarFun > UPtr
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
const VertexContainer _vertices
Vertex container.
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:47