|  | 
| void | computeValues (Eigen::Ref< Eigen::VectorXd > values) override | 
|  | Compute function values.  More... 
 | 
|  | 
| int | getDimension () const override | 
|  | Get dimension of the edge (dimension of the cost-function/constraint value vector)  More... 
 | 
|  | 
| bool | isLeastSquaresForm () const override | 
|  | Defines if the edge is formulated as Least-Squares form.  More... 
 | 
|  | 
| bool | isLinear () const override | 
|  | Return true if the edge is linear (and hence its Hessian is always zero)  More... 
 | 
|  | 
|  | TrapezoidalIntegralEqualityEdge (VectorVertex &x1, VectorVertex &u1, VectorVertex &x2, ScalarVertex &dt, StageEqualityConstraint::Ptr stage_eq, int k) | 
|  | 
| virtual | ~TrapezoidalIntegralEqualityEdge ()=default | 
|  | 
|  | Edge ()=delete | 
|  | 
| 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... 
 | 
|  | 
| virtual bool | providesHessian () const | 
|  | Return true if a custom Hessian is provided (e.g. computeHessian() is overwritten)  More... 
 | 
|  | 
| virtual bool | providesJacobian () const | 
|  | Return true if a custom Jacobian is provided (e.g. computeJacobian() 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 | 
|  | 
| int | getEdgeIdx () const | 
|  | Retrieve current edge index (warning, this value is determined within the related HyperGraph)  More... 
 | 
|  | 
| virtual double | computeSquaredNormOfValues () | 
|  | 
| virtual double | computeSumOfValues () | 
|  | 
| int | getNumFiniteVerticesLowerBounds () const | 
|  | 
| int | getNumFiniteVerticesUpperBounds () const | 
|  | 
| virtual int | getNumVertices () const =0 | 
|  | Return number of attached vertices.  More... 
 | 
|  | 
| virtual int | verticesDimension () const =0 | 
|  | Return the combined dimension of all attached vertices (excluding fixed vertex components)  More... 
 | 
|  | 
| virtual | ~EdgeInterface () | 
|  | Virtual destructor.  More... 
 | 
|  | 
  
  | 
        
          | bool corbo::TrapezoidalIntegralEqualityEdge::isLeastSquaresForm | ( |  | ) | const |  | inlineoverridevirtual | 
 
Defines if the edge is formulated as Least-Squares form. 
Least-squares cost terms are defined as  and the function values and Jacobian are computed for
 and the function values and Jacobian are computed for  rather than for
 rather than for  . Specialiezed least-squares solvers require the optimization problem to be defined in this particular form. Other solvers can automatically compute the square of least-squares edges if required. However, the other way round is more restrictive: general solvers might not cope with non-least-squares forms.
. Specialiezed least-squares solvers require the optimization problem to be defined in this particular form. Other solvers can automatically compute the square of least-squares edges if required. However, the other way round is more restrictive: general solvers might not cope with non-least-squares forms.
Note, in the LS-form case computeValues() computes e(x) and otherwise f(x).
- Returns
- true if the edge is given in LS-form 
Reimplemented from corbo::BaseEdge.
Definition at line 265 of file finite_differences_collocation_edges.h.