Crocoddyl
friction-cone.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2025, University of Edinburgh, University of Oxford,
5 // Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
9 
10 #ifndef CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
11 #define CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
12 
13 #include "crocoddyl/core/utils/deprecate.hpp"
14 #include "crocoddyl/multibody/fwd.hpp"
15 
16 namespace crocoddyl {
17 
27 template <typename _Scalar>
29  public:
30  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
31 
32  typedef _Scalar Scalar;
34  typedef typename MathBase::Vector3s Vector3s;
35  typedef typename MathBase::Matrix3s Matrix3s;
36  typedef typename MathBase::VectorXs VectorXs;
37  typedef typename MathBase::MatrixXs MatrixXs;
38  typedef typename MathBase::MatrixX3s MatrixX3s;
39  typedef typename MathBase::Quaternions Quaternions;
40 
54  const Matrix3s& R, const Scalar mu, std::size_t nf = 4,
55  const bool inner_appr = true, const Scalar min_nforce = Scalar(0.),
56  const Scalar max_nforce = std::numeric_limits<Scalar>::infinity());
57 
64 
68  explicit FrictionConeTpl();
69  ~FrictionConeTpl();
70 
80  void update();
81  DEPRECATED("Use update()",
82  void update(const Vector3s& normal, const Scalar mu,
83  const bool inner_appr = true,
84  const Scalar min_nforce = Scalar(0.),
85  const Scalar max_nforce =
86  std::numeric_limits<Scalar>::infinity()));
87 
97  template <typename NewScalar>
99 
103  const MatrixX3s& get_A() const;
104 
108  const VectorXs& get_ub() const;
109 
113  const VectorXs& get_lb() const;
114 
118  std::size_t get_nf() const;
119 
123  const Matrix3s& get_R() const;
124 
125  DEPRECATED("Use get_R.", Vector3s get_nsurf();)
126 
130  const Scalar get_mu() const;
131 
136  bool get_inner_appr() const;
137 
141  const Scalar get_min_nforce() const;
142 
146  const Scalar get_max_nforce() const;
147 
155  void set_R(const Matrix3s& R);
156 
157  DEPRECATED("Use set_R.", void set_nsurf(const Vector3s& nsurf);)
158 
165  void set_mu(const Scalar mu);
166 
174  void set_inner_appr(const bool inner_appr);
175 
182  void set_min_nforce(const Scalar min_nforce);
183 
190  void set_max_nforce(const Scalar max_nforce);
191 
192  FrictionConeTpl<Scalar>& operator=(const FrictionConeTpl<Scalar>& other);
193 
194  template <class Scalar>
195  friend std::ostream& operator<<(std::ostream& os,
196  const FrictionConeTpl<Scalar>& X);
197 
198  private:
199  std::size_t nf_;
200  MatrixX3s A_;
201  VectorXs ub_;
202  VectorXs lb_;
203  Matrix3s R_;
204  Scalar mu_;
205  bool inner_appr_;
207  Scalar min_nforce_;
208  Scalar max_nforce_;
209 };
210 
211 } // namespace crocoddyl
212 /* --- Details -------------------------------------------------------------- */
213 /* --- Details -------------------------------------------------------------- */
214 /* --- Details -------------------------------------------------------------- */
215 #include "crocoddyl/multibody/friction-cone.hxx"
216 
217 CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(crocoddyl::FrictionConeTpl)
218 
219 #endif // CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
This class encapsulates a friction cone.
void set_max_nforce(const Scalar max_nforce)
Modify the maximum normal force.
bool get_inner_appr() const
Return the label that describes the type of friction cone approximation (inner/outer)
const Scalar get_max_nforce() const
Return the maximum normal force.
const MatrixX3s & get_A() const
Return the matrix of friction cone.
void set_inner_appr(const bool inner_appr)
Modify the label that describes the type of friction cone approximation (inner/outer)
const VectorXs & get_lb() const
Return the lower bound of the friction cone.
const Scalar get_mu() const
Return the friction coefficient.
void set_min_nforce(const Scalar min_nforce)
Modify the maximum normal force.
std::size_t get_nf() const
Return the number of facets.
FrictionConeTpl()
Initialize the friction cone.
const VectorXs & get_ub() const
Return the upper bound of the friction cone.
void set_R(const Matrix3s &R)
Modify the rotation matrix that defines the cone orientation w.r.t. the inertial frame.
const Scalar get_min_nforce() const
Return the minimum normal force.
void set_mu(const Scalar mu)
Modify friction coefficient.
const Matrix3s & get_R() const
Return the surface normal vector.
FrictionConeTpl< NewScalar > cast() const
Cast the friction cone to a different scalar type.
void update()
Update the matrix and bound of friction cone inequalities in the world frame.
FrictionConeTpl(const FrictionConeTpl< Scalar > &cone)
Initialize the wrench cone.
FrictionConeTpl(const Matrix3s &R, const Scalar mu, std::size_t nf=4, const bool inner_appr=true, const Scalar min_nforce=Scalar(0.), const Scalar max_nforce=std::numeric_limits< Scalar >::infinity())
Initialize the wrench cone.