Crocoddyl
 
Loading...
Searching...
No Matches
WrenchConeTpl< _Scalar > Class Template Reference

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.
 
 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.
 
 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)
 
void set_inner_appr (const bool inner_appr)
 Modify the label that describes the type of friction cone approximation (inner/outer)
 
void set_max_nforce (const Scalar max_nforce)
 Modify the maximum normal force.
 
void set_min_nforce (const Scalar min_nforce)
 Modify the minium normal force.
 
void set_mu (const Scalar mu)
 Modify friction coefficient.
 
void set_R (const Matrix3s &R)
 Modify 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.
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Friends

template<class Scalar >
std::ostream & operator<< (std::ostream &os, const WrenchConeTpl< Scalar > &X)
 

Detailed Description

template<typename _Scalar>
class crocoddyl::WrenchConeTpl< _Scalar >

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.

Member Typedef Documentation

◆ MathBase

template<typename _Scalar >
typedef MathBaseTpl<Scalar> MathBase

Definition at line 37 of file wrench-cone.hpp.

◆ Vector2s

template<typename _Scalar >
typedef MathBase::Vector2s Vector2s

Definition at line 38 of file wrench-cone.hpp.

◆ Vector3s

template<typename _Scalar >
typedef MathBase::Vector3s Vector3s

Definition at line 39 of file wrench-cone.hpp.

◆ Matrix3s

template<typename _Scalar >
typedef MathBase::Matrix3s Matrix3s

Definition at line 40 of file wrench-cone.hpp.

◆ Matrix6s

template<typename _Scalar >
typedef MathBase::Matrix6s Matrix6s

Definition at line 41 of file wrench-cone.hpp.

◆ VectorXs

template<typename _Scalar >
typedef MathBase::VectorXs VectorXs

Definition at line 42 of file wrench-cone.hpp.

◆ MatrixXs

template<typename _Scalar >
typedef MathBase::MatrixXs MatrixXs

Definition at line 43 of file wrench-cone.hpp.

◆ MatrixX3s

template<typename _Scalar >
typedef MathBase::MatrixX3s MatrixX3s

Definition at line 44 of file wrench-cone.hpp.

◆ MatrixX6s

template<typename _Scalar >
typedef MathBase::MatrixX6s MatrixX6s

Definition at line 45 of file wrench-cone.hpp.

◆ Quaternions

template<typename _Scalar >
typedef MathBase::Quaternions Quaternions

Definition at line 46 of file wrench-cone.hpp.

Constructor & Destructor Documentation

◆ WrenchConeTpl()

template<typename _Scalar >
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
[in]RRotation matrix that defines the cone orientation w.r.t. the inertial frame
[in]muFriction coefficient
[in]boxDimension of the foot surface dim = (length, width)
[in]nfNumber of facets (default 4)
[in]inner_apprLabel that describes the type of friction cone approximation (inner/outer)
[in]min_nforceMinimum normal force (default 0.)
[in]max_nforceMaximum normal force (default inf number))

Member Function Documentation

◆ DEPRECATED()

template<typename _Scalar >
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.

Parameters
[in]coneWrench cone

◆ update()

template<typename _Scalar >
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.

◆ set_R()

template<typename _Scalar >
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.

◆ set_box()

template<typename _Scalar >
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.

◆ set_mu()

template<typename _Scalar >
void set_mu ( const Scalar  mu)

Modify friction coefficient.

Note that you need to run update for updating the inequality matrix and bounds.

◆ set_inner_appr()

template<typename _Scalar >
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.

◆ set_min_nforce()

template<typename _Scalar >
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.

◆ set_max_nforce()

template<typename _Scalar >
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.

Member Data Documentation

◆ Scalar

template<typename _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar

Definition at line 36 of file wrench-cone.hpp.


The documentation for this class was generated from the following files: