|  | 
|  | CombinedCompressedCollocationEdge (SystemDynamicsInterface::Ptr dynamics, StageCost::Ptr stage_cost, StageEqualityConstraint::Ptr stage_eq, StageInequalityConstraint::Ptr stage_ineq, bool eval_intermediate_constr, int k, VectorVertex &x1, VectorVertex &u1, ScalarVertex &dt, VectorVertex &u2, VectorVertex &x2) | 
|  | 
| void | computeEqualityValues (Eigen::Ref< Eigen::VectorXd > eq_values) override | 
|  | 
| void | computeInequalityValues (Eigen::Ref< Eigen::VectorXd > ineq_values) override | 
|  | 
| void | computeObjectiveValues (Eigen::Ref< Eigen::VectorXd > obj_values) override | 
|  | 
| int | getEqualityDimension () const override | 
|  | 
| int | getInequalityDimension () const override | 
|  | 
| int | getObjectiveDimension () const override | 
|  | 
| bool | isEqualityLinear () const override | 
|  | 
| bool | isInequalityLinear () const override | 
|  | 
| bool | isObjectiveLeastSquaresForm () const override | 
|  | 
| bool | isObjectiveLinear () const override | 
|  | Return true if the edge is linear (and hence its Hessian is always zero)  More... 
 | 
|  | 
| void | precompute () override | 
|  | 
| void | setCollocationMethod (QuadratureCollocationInterface::Ptr quadrature) | 
|  | 
| virtual | ~CombinedCompressedCollocationEdge () | 
|  | 
| int | getEqualityDimension () const override=0 | 
|  | 
| int | getInequalityDimension () const override=0 | 
|  | 
| int | getNumVertices () const override | 
|  | Return number of attached vertices.  More... 
 | 
|  | 
| int | getObjectiveDimension () const override=0 | 
|  | 
| const VertexInterface * | getVertex (int idx) const override | 
|  | 
| VertexInterface * | getVertexRaw (int idx) override | 
|  | Get access to vertex with index idx(0 <= idx < numVertices)  More...
 | 
|  | 
|  | MixedEdge ()=delete | 
|  | 
| int | verticesDimension () const override | 
|  | Return the combined dimension of all attached vertices (excluding fixed vertex components)  More... 
 | 
|  | 
| virtual void | computeConstraintHessians (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &eq_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &ineq_jacobian_i, Eigen::Ref< Eigen::MatrixXd > eq_hessian_ij, Eigen::Ref< Eigen::MatrixXd > ineq_hessian_ij, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr) | 
|  | 
| virtual void | computeConstraintHessiansInc (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &eq_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &ineq_jacobian_i, Eigen::Ref< Eigen::MatrixXd > eq_hessian_ij, Eigen::Ref< Eigen::MatrixXd > ineq_hessian_ij, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr) | 
|  | 
| virtual void | computeConstraintJacobians (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > eq_jacobian, Eigen::Ref< Eigen::MatrixXd > ineq_jacobian, const double *eq_multipliers=nullptr, const double *ineq_multipliers=nullptr) | 
|  | 
| virtual void | computeEqualityHessian (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 | computeEqualityHessianInc (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 | computeEqualityJacobian (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr) | 
|  | 
| virtual void | computeHessians (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &obj_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &eq_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &ineq_jacobian_i, Eigen::Ref< Eigen::MatrixXd > obj_hessian_ij, Eigen::Ref< Eigen::MatrixXd > eq_hessian_ij, Eigen::Ref< Eigen::MatrixXd > ineq_hessian_ij, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr, double weight_obj=1.0) | 
|  | 
| virtual void | computeHessiansInc (int vtx_idx_i, int vtx_idx_j, const Eigen::Ref< const Eigen::MatrixXd > &obj_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &eq_jacobian_i, const Eigen::Ref< const Eigen::MatrixXd > &ineq_jacobian_i, Eigen::Ref< Eigen::MatrixXd > obj_hessian_ij, Eigen::Ref< Eigen::MatrixXd > eq_hessian_ij, Eigen::Ref< Eigen::MatrixXd > ineq_hessian_ij, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr, double weight_obj=1.0) | 
|  | 
| virtual void | computeInequalityHessian (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 | computeInequalityHessianInc (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 | computeInequalityJacobian (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr) | 
|  | 
| virtual void | computeJacobians (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > obj_jacobian, Eigen::Ref< Eigen::MatrixXd > eq_jacobian, Eigen::Ref< Eigen::MatrixXd > ineq_jacobian, const double *obj_multipliers=nullptr, const double *eq_multipliers=nullptr, const double *ineq_multipliers=nullptr) | 
|  | 
| virtual void | computeObjectiveHessian (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 | computeObjectiveHessianInc (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 | computeObjectiveJacobian (int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr) | 
|  | 
| virtual double | computeSquaredNormOfObjectiveValues () | 
|  | 
| virtual double | computeSumOfObjectiveValues () | 
|  | 
| void | computeValues (Eigen::Ref< Eigen::VectorXd > values) final | 
|  | Compute function values.  More... 
 | 
|  | 
| int | getDimension () const override | 
|  | Get dimension of the edge (dimension of the cost-function/constraint value vector)  More... 
 | 
|  | 
| void | reserveCacheMemory (int num_value_vectors, int num_jacobians) | 
|  | 
| void | reserveValuesCacheMemory (int num_obj_values, int num_eq_values, int num_ineq_values) | 
|  | 
| void | reserveJacobiansCacheMemory (int num_obj_jacobians, int num_eq_jacobians, int num_ineq_jacobians) | 
|  | 
| void | computeObjectiveValuesCached () | 
|  | Call computeObjectiveValues() and store result to the internal cache.  More... 
 | 
|  | 
| void | computeSquaredNormOfObjectiveValuesCached () | 
|  | compute the specialied squared-norm method for computing the values (note only the first element in the values cache is used)  More... 
 | 
|  | 
| void | computeEqualityValuesCached () | 
|  | Call computeEqualityValues() and store result to the internal cache.  More... 
 | 
|  | 
| void | computeInequalityValuesCached () | 
|  | Call computeInequalityValues() and store result to the internal cache.  More... 
 | 
|  | 
| EdgeCache & | getObjectiveCache () | 
|  | 
| const EdgeCache & | getObjectiveCache () const | 
|  | 
| EdgeCache & | getEqualityCache () | 
|  | 
| const EdgeCache & | getEqualityCache () const | 
|  | 
| EdgeCache & | getInequalityCache () | 
|  | 
| const EdgeCache & | getInequalityCache () const | 
|  | 
| int | getEdgeObjectiveIdx () const | 
|  | Retrieve current edge index (warning, this value is determined within the related HyperGraph)  More... 
 | 
|  | 
| int | getEdgeEqualityIdx () const | 
|  | 
| int | getEdgeInequalityIdx () const | 
|  | 
| 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... 
 | 
|  |