Template Class WrenchConeTpl
Defined in File wrench-cone.hpp
Class Documentation
-
template<typename _Scalar>
class WrenchConeTpl This class encapsulates a wrench cone.
A wrench cone is a 6D polyhedral convex cone that characterizes feasible contact wrench. The wrench cone is derived in the case of rectangular support areas, which is of practical importance since most humanoid robot feet can be adequately approximated by rectangles. For more details read: S. Caron et. al. Stability of surface contacts for humanoid robots: Closed-form formulae of the Contact Wrench Cone for rectangular support areas (https://hal.archives-ouvertes.fr/hal-02108449/document)
/sa
FrictionConeTpl,CoPSupportTplPublic Types
-
typedef MathBaseTpl<Scalar> MathBase
Public Functions
-
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.
- Parameters:
R – [in] Rotation matrix that defines the cone orientation w.r.t. the inertial frame
mu – [in] Friction coefficient
box – [in] Dimension of the foot surface dim = (length, width)
nf – [in] Number of facets (default 4)
inner_appr – [in] Label that describes the type of friction cone approximation (inner/outer)
min_nforce – [in] Minimum normal force (default 0.)
max_nforce – [in] Maximum normal force (default inf number))
- 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.
- Parameters:
cone – [in] Wrench cone
-
explicit WrenchConeTpl()
Initialize the wrench cone.
-
~WrenchConeTpl()
-
void update()
Update the matrix of wrench cone inequalities in the world frame.
This matrix-vector pair describes the linearized Coulomb friction model as follow: \( -ub \leq A \times w \leq -lb \), where wrench, \( w \), is expressed in the inertial frame located at the center of the rectangular foot contact area (length, width) with axes parallel to those of the world frame.
- DEPRECATED ("Use update().", void update(const Matrix3s &R, const Scalar mu, const Vector2s &box, const Scalar min_nforce=Scalar(0.), const Scalar max_nforce=std::numeric_limits< Scalar >::infinity()))
-
template<typename NewScalar>
WrenchConeTpl<NewScalar> cast() const Cast the wrench cone to a different scalar type.
It is useful for operations requiring different precision or scalar types.
- Template Parameters:
NewScalar – The new scalar type to cast to.
- Returns:
WrenchConeTpl<NewScalar> A wrench cone with the new scalar type.
-
std::size_t get_nf() const
Return the number of facets.
-
const Matrix3s &get_R() const
Return the rotation matrix that defines the cone orientation w.r.t. the inertial frame.
-
const Scalar get_mu() const
Return friction coefficient.
-
bool get_inner_appr() const
Return the label that describes the type of friction cone approximation (inner/outer)
-
const Scalar get_min_nforce() const
Return the minimum normal force.
-
const Scalar get_max_nforce() const
Return the maximum normal force.
-
void set_R(const Matrix3s &R)
Modify the rotation matrix that defines the cone orientation w.r.t. the inertial frame.
Note that you need to run
updatefor updating the inequality matrix and bounds.
-
void set_box(const Vector2s &box)
Modify dimension of the foot surface dim = (length, width)
Note that you need to run
updatefor updating the inequality matrix and bounds.
-
void set_mu(const Scalar mu)
Modify friction coefficient.
Note that you need to run
updatefor updating the inequality matrix and bounds.
-
void set_inner_appr(const bool inner_appr)
Modify the label that describes the type of friction cone approximation (inner/outer)
Note that you need to run
updatefor updating the inequality matrix and bounds.
-
void set_min_nforce(const Scalar min_nforce)
Modify the minium normal force.
Note that you need to run
updatefor updating the inequality matrix and bounds.
-
void set_max_nforce(const Scalar max_nforce)
Modify the maximum normal force.
Note that you need to run
updatefor updating the inequality matrix and bounds.
-
WrenchConeTpl<Scalar> &operator=(const WrenchConeTpl<Scalar> &other)
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
Friends
-
template<class Scalar>
friend std::ostream &operator<<(std::ostream &os, const WrenchConeTpl<Scalar> &X)
-
typedef MathBaseTpl<Scalar> MathBase