pgs-solver.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022-2024 INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_pgs_solver_hpp__
6 #define __pinocchio_algorithm_pgs_solver_hpp__
7 
10 
11 namespace pinocchio
12 {
13 
15  template<typename _Scalar>
17  {
18  typedef _Scalar Scalar;
20  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> VectorXs;
21 
22  explicit PGSContactSolverTpl(const int problem_size)
24  , x(problem_size)
26  {
27  }
28 
40  template<
41  typename MatrixLike,
42  typename VectorLike,
43  typename ConstraintAllocator,
44  typename VectorLikeOut>
45  bool solve(
46  const MatrixLike & G,
47  const Eigen::MatrixBase<VectorLike> & g,
48  const std::vector<CoulombFrictionConeTpl<Scalar>, ConstraintAllocator> & cones,
49  const Eigen::DenseBase<VectorLikeOut> & x,
50  const Scalar over_relax = Scalar(1));
51 
52  protected:
55 #ifdef PINOCCHIO_WITH_HPP_FCL
56  using Base::timer;
57 #endif // PINOCCHIO_WITH_HPP_FCL
58 
59  }; // struct PGSContactSolverTpl
60 } // namespace pinocchio
61 
62 #include "pinocchio/algorithm/pgs-solver.hxx"
63 
64 #endif // ifndef __pinocchio_algorithm_pgs_solver_hpp__
pinocchio::CoulombFrictionConeTpl
&#160;
Definition: algorithm/constraints/coulomb-friction-cone.hpp:20
pinocchio::PGSContactSolverTpl::x
VectorXs x
Previous temporary value of the optimum.
Definition: pgs-solver.hpp:54
pinocchio::PGSContactSolverTpl::solve
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 initia...
pinocchio::PGSContactSolverTpl::x_previous
VectorXs x_previous
Definition: pgs-solver.hpp:54
contact-solver-base.hpp
pinocchio::ContactSolverBaseTpl
Definition: algorithm/contact-solver-base.hpp:19
pinocchio::PGSContactSolverTpl
Projected Gauss Siedel solver.
Definition: pgs-solver.hpp:16
pinocchio::PGSContactSolverTpl::Base
ContactSolverBaseTpl< Scalar > Base
Definition: pgs-solver.hpp:19
pinocchio::PGSContactSolverTpl::PGSContactSolverTpl
PGSContactSolverTpl(const int problem_size)
Definition: pgs-solver.hpp:22
pinocchio::PGSContactSolverTpl::Scalar
_Scalar Scalar
Definition: pgs-solver.hpp:18
fwd.hpp
pinocchio::PGSContactSolverTpl::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXs
Definition: pgs-solver.hpp:20
pinocchio::ContactSolverBaseTpl::problem_size
int problem_size
Size of the problem.
Definition: algorithm/contact-solver-base.hpp:114
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:40