5 #ifndef __pinocchio_algorithm_constraints_coulomb_friction_cone_hpp__ 
    6 #define __pinocchio_algorithm_constraints_coulomb_friction_cone_hpp__ 
   15   template<
typename Scalar>
 
   19   template<
typename _Scalar>
 
   24     typedef Eigen::Matrix<Scalar, 3, 1> 
Vector3;
 
   32       assert(
mu >= 0 && 
"mu must be positive");
 
   44       return mu == other.
mu;
 
   50       return !(*
this == other);
 
   57     template<
typename Vector3Like>
 
   60       assert(
mu >= 0 && 
"mu must be positive");
 
   61       assert(prec >= 0 && 
"prec should be positive");
 
   62       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
   63       return f.template head<2>().norm() <= 
mu * 
f[2] + prec;
 
   70     template<
typename Vector3Like>
 
   72       project(
const Eigen::MatrixBase<Vector3Like> & x)
 const 
   74       assert(
mu >= 0 && 
"mu must be positive");
 
   75       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
   80       const Eigen::Matrix<Scalar, 2, 1> 
t = 
x.template head<2>();
 
   83       if (
mu * t_norm <= -z)
 
   84         return Vector3Plain::Zero();
 
   85       else if (t_norm <= mu_z)
 
   92         res.template head<2>() = (
mu / t_norm) * 
t;
 
  107     template<
typename Vector3Like>
 
  109       const Eigen::MatrixBase<Vector3Like> & x, 
const Eigen::MatrixBase<Vector3Like> & R)
 const 
  111       assert(
mu >= 0 && 
"mu must be positive");
 
  112       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
  114       assert(
R(2) > 0 && 
"R(2) must be strictly positive");
 
  115       Scalar weighted_mu = 
mu * math::sqrt(
R(0) / 
R(2));
 
  117       Vector3Plain R_sqrt = 
R.cwiseSqrt();
 
  118       Vector3Plain R_sqrt_times_x = (R_sqrt.array() * 
x.array()).matrix();
 
  119       Vector3Plain 
res = (weighted_cone.project(R_sqrt_times_x).array() / R_sqrt.array()).matrix();
 
  128     template<
typename Vector3Like>
 
  130       computeNormalCorrection(
const Eigen::MatrixBase<Vector3Like> & 
v)
 const 
  132       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
  136       res.template head<2>().setZero();
 
  137       res[2] = 
mu * 
v.template head<2>().norm();
 
  146     template<
typename Vector3Like>
 
  148       computeRadialProjection(
const Eigen::MatrixBase<Vector3Like> & 
f)
 const 
  150       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
  154       const auto & ft = 
f.template head<2>();
 
  155       const Scalar ft_norm = ft.norm();
 
  161         res.template head<2>() = 
Scalar(mu_fz / ft_norm) * ft;
 
  164         res.template head<2>() = ft;
 
  169     template<
typename Vector3Like1, 
typename Vector3Like2>
 
  170     Scalar computeContactComplementarity(
 
  171       const Eigen::MatrixBase<Vector3Like1> & 
v, 
const Eigen::MatrixBase<Vector3Like2> & 
f)
 const 
  174       return math::fabs(
f.dot(Vector3Plain(
v + computeNormalCorrection(
v))));
 
  177     template<
typename Vector3Like1, 
typename Vector3Like2>
 
  179       const Eigen::MatrixBase<Vector3Like1> & 
v, 
const Eigen::MatrixBase<Vector3Like2> & 
f)
 const 
  181       return math::fabs(
f.dot(
v));
 
  201   template<
typename _Scalar>
 
  213       assert(
mu >= 0 && 
"mu must be positive");
 
  225       return mu == other.
mu;
 
  231       return !(*
this == other);
 
  238     template<
typename Vector3Like>
 
  241       assert(
mu >= 0 && 
"mu must be positive");
 
  242       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
  243       return mu * 
v.template head<2>().norm() <= 
v[2] + prec;
 
  247     template<
typename Vector3Like>
 
  249       project(
const Eigen::MatrixBase<Vector3Like> & x)
 const 
  251       assert(
mu >= 0 && 
"mu must be positive");
 
  252       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
  256       const Eigen::Matrix<Scalar, 2, 1> 
t = 
x.template head<2>();
 
  257       const Scalar t_norm = 
t.norm();
 
  259       if (t_norm <= -
mu * z)
 
  260         return Vector3Plain::Zero();
 
  261       else if (
mu * t_norm <= z)
 
  268         res.template head<2>() = 
t;
 
  269         res[2] = 
mu * t_norm;
 
  296 #endif // ifndef __pinocchio_algorithm_constraints_coulomb_friction_cone_hpp__