9 #ifndef CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
10 #define CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
12 #include "crocoddyl/core/mathbase.hpp"
13 #include "crocoddyl/core/utils/deprecate.hpp"
14 #include "crocoddyl/multibody/fwd.hpp"
27 template <
typename _Scalar>
30 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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;
59 const Matrix3s& R,
const Scalar mu, std::size_t nf = 4,
60 const bool inner_appr =
true,
const Scalar min_nforce = Scalar(0.),
61 const Scalar max_nforce = std::numeric_limits<Scalar>::infinity());
64 std::size_t nf = 4,
const bool inner_appr =
true,
65 const Scalar min_nforce = Scalar(0.),
66 const Scalar max_nforce =
67 std::numeric_limits<Scalar>::infinity());)
88 void update(
const Vector3s& normal,
const Scalar mu,
89 const bool inner_appr =
true,
90 const Scalar min_nforce = Scalar(0.),
91 const Scalar max_nforce =
92 std::numeric_limits<Scalar>::infinity()));
119 DEPRECATED(
"Use get_R.", Vector3s get_nsurf();)
151 DEPRECATED(
"Use set_R.",
void set_nsurf(
const Vector3s& nsurf);)
188 template <
class Scalar>
189 friend std::ostream& operator<<(std::ostream& os,
209 #include "crocoddyl/multibody/friction-cone.hxx"
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.
void update()
Update the matrix and bound of friction cone inequalities in the world frame.
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.
DEPRECATED("Use constructor based on rotation matrix.", FrictionConeTpl(const Vector3s &normal, 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());) FrictionConeTpl(const FrictionConeTpl< Scalar > &cone)
Initialize the wrench cone.