Public Types | Public Member Functions | Protected Attributes | List of all members
pinocchio::PGSContactSolverTpl< _Scalar > Struct Template Reference

Projected Gauss Siedel solver. More...

#include <pgs-solver.hpp>

Inheritance diagram for pinocchio::PGSContactSolverTpl< _Scalar >:
Inheritance graph
[legend]

Public Types

typedef ContactSolverBaseTpl< ScalarBase
 
typedef _Scalar Scalar
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXs
 
- Public Types inherited from pinocchio::ContactSolverBaseTpl< _Scalar >
typedef _Scalar Scalar
 

Public Member Functions

 PGSContactSolverTpl (const int problem_size)
 
template<typename MatrixLike , typename VectorLike , typename ConstraintAllocator , typename VectorLikeOut >
bool solve (const MatrixLike &G, const Eigen::MatrixBase< VectorLike > &g, const std::vector< CoulombFrictionConeTpl< Scalar >, ConstraintAllocator > &cones, const Eigen::DenseBase< VectorLikeOut > &x, const Scalar over_relax=Scalar(1))
 Solve the constrained conic problem composed of problem data (G,g,cones) and starting from the initial guess. More...
 
- Public Member Functions inherited from pinocchio::ContactSolverBaseTpl< _Scalar >
 ContactSolverBaseTpl (const int problem_size)
 
Scalar getAbsoluteConvergenceResidual () const
 Returns the value of the absolute residual value corresponding to the contact complementary conditions. More...
 
Scalar getAbsolutePrecision () const
 Get the absolute precision requested. More...
 
int getIterationCount () const
 Get the number of iterations achieved by the solver. More...
 
int getMaxIterations () const
 Get the maximum number of iterations allowed. More...
 
int getProblemSize () const
 Returns the size of the problem. More...
 
Scalar getRelativeConvergenceResidual () const
 Returns the value of the relative residual value corresponding to the difference between two successive iterates (infinity norms). More...
 
Scalar getRelativePrecision () const
 Get the relative precision requested. More...
 
void setAbsolutePrecision (const Scalar absolute_precision)
 Set the absolute precision for the problem. More...
 
void setMaxIterations (const int max_it)
 Set the maximum number of iterations. More...
 
void setRelativePrecision (const Scalar relative_precision)
 Set the relative precision for the problem. More...
 

Protected Attributes

VectorXs x
 Previous temporary value of the optimum. More...
 
VectorXs x_previous
 
- Protected Attributes inherited from pinocchio::ContactSolverBaseTpl< _Scalar >
Scalar absolute_precision
 Desired absolute precision. More...
 
Scalar absolute_residual
 Absolule convergence residual value. More...
 
int it
 Number of iterations needed to achieve convergence. More...
 
int max_it
   More...
 
int problem_size
 Size of the problem. More...
 
Scalar relative_precision
 Desired relative precision. More...
 
Scalar relative_residual
 Relative convergence residual value. More...
 

Detailed Description

template<typename _Scalar>
struct pinocchio::PGSContactSolverTpl< _Scalar >

Projected Gauss Siedel solver.

Definition at line 16 of file pgs-solver.hpp.

Member Typedef Documentation

◆ Base

template<typename _Scalar >
typedef ContactSolverBaseTpl<Scalar> pinocchio::PGSContactSolverTpl< _Scalar >::Base

Definition at line 19 of file pgs-solver.hpp.

◆ Scalar

template<typename _Scalar >
typedef _Scalar pinocchio::PGSContactSolverTpl< _Scalar >::Scalar

Definition at line 18 of file pgs-solver.hpp.

◆ VectorXs

template<typename _Scalar >
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> pinocchio::PGSContactSolverTpl< _Scalar >::VectorXs

Definition at line 20 of file pgs-solver.hpp.

Constructor & Destructor Documentation

◆ PGSContactSolverTpl()

template<typename _Scalar >
pinocchio::PGSContactSolverTpl< _Scalar >::PGSContactSolverTpl ( const int  problem_size)
inlineexplicit

Definition at line 22 of file pgs-solver.hpp.

Member Function Documentation

◆ solve()

template<typename _Scalar >
template<typename MatrixLike , typename VectorLike , typename ConstraintAllocator , typename VectorLikeOut >
bool pinocchio::PGSContactSolverTpl< _Scalar >::solve ( const MatrixLike &  G,
const Eigen::MatrixBase< VectorLike > &  g,
const std::vector< CoulombFrictionConeTpl< Scalar >, ConstraintAllocator > &  cones,
const Eigen::DenseBase< VectorLikeOut > &  x,
const Scalar  over_relax = Scalar(1) 
)

Solve the constrained conic problem composed of problem data (G,g,cones) and starting from the initial guess.

Parameters
[in]GSymmetric PSD matrix representing the Delassus of the contact problem.
[in]gFree contact acceleration or velicity associted with the contact problem.
[in]conesVector of conic constraints.
[in,out]xInitial guess and output solution of the problem
[in]over_relaxOver relaxation value
Returns
True if the problem has converged.

Member Data Documentation

◆ x

template<typename _Scalar >
VectorXs pinocchio::PGSContactSolverTpl< _Scalar >::x
protected

Previous temporary value of the optimum.

Definition at line 54 of file pgs-solver.hpp.

◆ x_previous

template<typename _Scalar >
VectorXs pinocchio::PGSContactSolverTpl< _Scalar >::x_previous
protected

Definition at line 54 of file pgs-solver.hpp.


The documentation for this struct was generated from the following file:


pinocchio
Author(s):
autogenerated on Wed Jun 19 2024 02:41:19