9 #ifndef CROCODDYL_MULTIBODY_WRENCH_CONE_HPP_
10 #define CROCODDYL_MULTIBODY_WRENCH_CONE_HPP_
12 #include "crocoddyl/core/mathbase.hpp"
13 #include "crocoddyl/core/utils/deprecate.hpp"
14 #include "crocoddyl/multibody/fwd.hpp"
31 template <
typename _Scalar>
34 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
36 typedef _Scalar Scalar;
38 typedef typename MathBase::Vector2s Vector2s;
39 typedef typename MathBase::Vector3s Vector3s;
40 typedef typename MathBase::Matrix3s Matrix3s;
41 typedef typename MathBase::Matrix6s Matrix6s;
42 typedef typename MathBase::VectorXs VectorXs;
43 typedef typename MathBase::MatrixXs MatrixXs;
44 typedef typename MathBase::MatrixX3s MatrixX3s;
45 typedef typename MathBase::MatrixX6s MatrixX6s;
46 typedef typename MathBase::Quaternions Quaternions;
67 const Matrix3s& R,
const Scalar mu,
const Vector2s& box,
68 const std::size_t nf = 4,
const bool inner_appr =
true,
69 const Scalar min_nforce = Scalar(0.),
70 const Scalar max_nforce = std::numeric_limits<Scalar>::infinity());
73 const Vector2s& box, std::size_t nf,
74 const Scalar min_nforce,
75 const Scalar max_nforce =
76 std::numeric_limits<Scalar>::infinity());)
97 void update(
const Matrix3s& R,
const Scalar mu,
99 const Scalar min_nforce = Scalar(0.),
100 const Scalar max_nforce =
101 std::numeric_limits<Scalar>::infinity()));
207 template <
class Scalar>
208 friend std::ostream& operator<<(std::ostream& os,
227 #include "crocoddyl/multibody/wrench-cone.hxx"
This class encapsulates a wrench 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)
WrenchConeTpl(const Matrix3s &R, const Scalar mu, const Vector2s &box, const 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.
void set_box(const Vector2s &box)
Modify dimension of the foot surface dim = (length, width)
const Scalar get_max_nforce() const
Return the maximum normal force.
WrenchConeTpl()
Initialize the wrench 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 inequalities.
const Scalar get_mu() const
Return friction coefficient.
void set_min_nforce(const Scalar min_nforce)
Modify the minium normal force.
std::size_t get_nf() const
Return the number of facets.
const MatrixX6s & get_A() const
Return the matrix of wrench cone.
const VectorXs & get_ub() const
Return the upper bound of inequalities.
void set_R(const Matrix3s &R)
Modify the rotation matrix that defines the cone orientation w.r.t. the inertial frame.
const Vector2s & get_box() const
Return dimension of the foot surface dim = (length, width)
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 rotation matrix that defines the cone orientation w.r.t. the inertial frame.
void update()
Update the matrix of wrench cone inequalities in the world frame.
DEPRECATED("Use constructor that includes inner_appr", WrenchConeTpl(const Matrix3s &R, const Scalar mu, const Vector2s &box, std::size_t nf, const Scalar min_nforce, const Scalar max_nforce=std::numeric_limits< Scalar >::infinity());) WrenchConeTpl(const WrenchConeTpl< Scalar > &cone)
Initialize the wrench cone.