Crocoddyl
FrictionConeTpl< _Scalar > Class Template Reference

This class encapsulates a friction cone. More...

#include <friction-cone.hpp>

Public Types

typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::Matrix3s Matrix3s
 
typedef MathBase::MatrixX3s MatrixX3s
 
typedef MathBase::MatrixXs MatrixXs
 
typedef MathBase::Quaternions Quaternions
 
typedef MathBase::Vector3s Vector3s
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 FrictionConeTpl ()
 Initialize the friction cone.
 
 FrictionConeTpl (const Matrix3s &R, 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())
 Initialize the wrench cone. More...
 
 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. More...
 
 DEPRECATED ("Use update()", void update(const Vector3s &normal, const Scalar mu, const bool inner_appr=true, const Scalar min_nforce=Scalar(0.), const Scalar max_nforce=std::numeric_limits< Scalar >::infinity()))
 
const MatrixX3s & get_A () const
 Return the matrix of friction cone.
 
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 the friction cone.
 
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 the friction coefficient.
 
std::size_t get_nf () const
 Return the number of facets.
 
const Matrix3s & get_R () const
 Return the surface normal vector.
 
const VectorXs & get_ub () const
 Return the upper bound of the friction cone.
 
FrictionConeTpl< Scalar > & operator= (const FrictionConeTpl< Scalar > &other)
 
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 maximum 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 and bound of friction 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 FrictionConeTpl< Scalar > &X)
 

Detailed Description

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

This class encapsulates a friction cone.

A friction cone is a 3D cone that characterizes feasible contact wrench. The friction cone defines a linearized version (pyramid) with a predefined number of facets.

/sa WrenchConeTpl

Definition at line 28 of file friction-cone.hpp.

Constructor & Destructor Documentation

◆ FrictionConeTpl()

FrictionConeTpl ( const Matrix3s &  R,
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() 
)

Initialize the wrench cone.

Parameters
[in]RRotation matrix that defines the cone orientation w.r.t. the inertial frame
[in]muFriction coefficient
[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()

DEPRECATED ( "Use constructor based on rotation matrix."  ,
FrictionConeTpl< _Scalar >(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());   
) const &

Initialize the wrench cone.

Parameters
[in]coneFriction cone

◆ update()

void update ( )

Update the matrix and bound of friction 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 with axes parallel to those of the world frame.

◆ set_R()

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_mu()

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()

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()

void set_min_nforce ( const Scalar  min_nforce)

Modify the maximum normal force.

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

◆ set_max_nforce()

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.


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