crocoddyl
1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
|
|
9 #ifndef CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
10 #define CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
12 #include "crocoddyl/multibody/fwd.hpp"
13 #include "crocoddyl/core/mathbase.hpp"
14 #include "crocoddyl/core/utils/deprecate.hpp"
26 template <
typename _Scalar>
29 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
31 typedef _Scalar Scalar;
33 typedef typename MathBase::Vector3s Vector3s;
34 typedef typename MathBase::Matrix3s Matrix3s;
35 typedef typename MathBase::VectorXs VectorXs;
36 typedef typename MathBase::MatrixXs MatrixXs;
37 typedef typename MathBase::MatrixX3s MatrixX3s;
38 typedef typename MathBase::Quaternions Quaternions;
55 FrictionConeTpl(
const Matrix3s& R,
const Scalar mu, std::size_t nf = 4,
const bool inner_appr =
true,
56 const Scalar min_nforce = Scalar(0.),
57 const Scalar max_nforce = std::numeric_limits<Scalar>::infinity());
58 DEPRECATED(
"Use constructor based on rotation matrix.",
59 FrictionConeTpl(
const Vector3s& normal,
const Scalar mu, std::size_t nf = 4,
const bool inner_appr =
true,
60 const Scalar min_nforce = Scalar(0.),
61 const Scalar max_nforce = std::numeric_limits<Scalar>::infinity());)
80 DEPRECATED(
"Use update()",
void update(
const Vector3s& normal,
const Scalar mu,
const bool inner_appr =
true,
81 const Scalar min_nforce = Scalar(0.),
82 const Scalar max_nforce = std::numeric_limits<Scalar>::infinity()));
87 const MatrixX3s&
get_A()
const;
92 const VectorXs&
get_ub()
const;
97 const VectorXs&
get_lb()
const;
102 std::size_t
get_nf()
const;
107 const Matrix3s&
get_R()
const;
109 DEPRECATED(
"Use get_R.", Vector3s get_nsurf();)
114 const Scalar
get_mu()
const;
136 void set_R(
const Matrix3s& R);
138 DEPRECATED(
"Use set_R.",
void set_nsurf(
const Vector3s& nsurf);)
145 void set_mu(
const Scalar mu);
170 template <
class Scalar>
189 #include "crocoddyl/multibody/friction-cone.hxx"
191 #endif // CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
const VectorXs & get_ub() const
Return the upper bound of the friction 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.
const VectorXs & get_lb() const
Return the lower bound of the friction cone.
const Scalar get_mu() const
Return the friction coefficient.
std::size_t get_nf() const
Return the number of facets.
FrictionConeTpl()
Initialize the friction cone.
bool get_inner_appr() const
Return the label that describes the type of friction cone approximation (inner/outer)
void set_mu(const Scalar mu)
Modify friction coefficient.
This class encapsulates a friction cone.
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.
void set_min_nforce(const Scalar min_nforce)
Modify the maximum normal force.
void set_max_nforce(const Scalar max_nforce)
Modify the maximum normal force.
const Scalar get_max_nforce() const
Return the maximum normal force.
void set_inner_appr(const bool inner_appr)
Modify the label that describes the type of friction cone approximation (inner/outer)
const MatrixX3s & get_A() const
Return the matrix of 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.