This class encapsulates a wrench cone. More...
#include <wrench-cone.hpp>
Public Types | |
typedef MathBaseTpl< Scalar > | MathBase |
typedef MathBase::Matrix3s | Matrix3s |
typedef MathBase::Matrix6s | Matrix6s |
typedef MathBase::MatrixX3s | MatrixX3s |
typedef MathBase::MatrixX6s | MatrixX6s |
typedef MathBase::MatrixXs | MatrixXs |
typedef MathBase::Quaternions | Quaternions |
typedef MathBase::Vector2s | Vector2s |
typedef MathBase::Vector3s | Vector3s |
typedef MathBase::VectorXs | VectorXs |
Public Member Functions | |
WrenchConeTpl () | |
Initialize the wrench cone. | |
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. More... | |
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. More... | |
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())) | |
const MatrixX6s & | get_A () const |
Return the matrix of wrench cone. | |
const Vector2s & | get_box () const |
Return dimension of the foot surface dim = (length, width) | |
bool | get_inner_appr () const |
Return 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_max_nforce () const |
Return the maximum normal force. | |
const Scalar | get_min_nforce () const |
Return the minimum normal force. | |
const Scalar | get_mu () const |
Return friction coefficient. | |
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 VectorXs & | get_ub () const |
Return the upper bound of inequalities. | |
WrenchConeTpl< Scalar > & | operator= (const WrenchConeTpl< Scalar > &other) |
void | set_box (const Vector2s &box) |
Modify dimension of the foot surface dim = (length, width) More... | |
void | set_inner_appr (const bool inner_appr) |
Modify the label that describes the type of friction cone approximation (inner/outer) More... | |
void | set_max_nforce (const Scalar max_nforce) |
Modify the maximum normal force. More... | |
void | set_min_nforce (const Scalar min_nforce) |
Modify the minium normal force. More... | |
void | set_mu (const Scalar mu) |
Modify friction coefficient. More... | |
void | set_R (const Matrix3s &R) |
Modify the rotation matrix that defines the cone orientation w.r.t. the inertial frame. More... | |
void | update () |
Update the matrix of wrench cone inequalities in the world frame. More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
Friends | |
template<class Scalar > | |
std::ostream & | operator<< (std::ostream &os, const WrenchConeTpl< Scalar > &X) |
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
, CoPSupportTpl
Definition at line 32 of file wrench-cone.hpp.
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.
[in] | R | Rotation matrix that defines the cone orientation w.r.t. the inertial frame |
[in] | mu | Friction coefficient |
[in] | box | Dimension of the foot surface dim = (length, width) |
[in] | nf | Number of facets (default 4) |
[in] | inner_appr | Label that describes the type of friction cone approximation (inner/outer) |
[in] | min_nforce | Minimum normal force (default 0.) |
[in] | max_nforce | Maximum normal force (default inf number)) |
DEPRECATED | ( | "Use constructor that includes inner_appr" | , |
WrenchConeTpl< _Scalar >(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()); | |||
) | const & |
Initialize the wrench cone.
[in] | cone | Wrench cone |
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.
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 update
for 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 update
for updating the inequality matrix and bounds.
void set_mu | ( | const Scalar | mu | ) |
Modify friction coefficient.
Note that you need to run update
for 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 update
for 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 update
for 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 update
for updating the inequality matrix and bounds.