force_control_collection
Classes | Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
ForceColl::Contact Class Referenceabstract

Contact. More...

#include <Contact.h>

Inheritance diagram for ForceColl::Contact:
Inheritance graph
[legend]

Classes

struct  VertexWithRidge
 Vertex with ridges. More...
 

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Contact (const std::string &name, std::optional< sva::ForceVecd > maxWrench=std::nullopt)
 Constructor. More...
 
virtual std::string type () const =0
 Get type of contact. More...
 
int ridgeNum () const
 Get the number of ridges. More...
 
virtual void updateGlobalVertices (const sva::PTransformd &pose)=0
 Update graspMat_ and vertexWithRidgeList_ according to the input pose. More...
 
sva::ForceVecd calcWrench (const Eigen::VectorXd &wrenchRatio, const Eigen::Vector3d &momentOrigin=Eigen::Vector3d::Zero()) const
 Calculate wrench. More...
 
sva::ForceVecd calcLocalWrench (const Eigen::VectorXd &wrenchRatio) const
 Calculate the local wrench. More...
 
virtual void addToGUI (mc_rtc::gui::StateBuilder &gui, const std::vector< std::string > &category, double forceScale=constants::defaultForceScale, double fricPyramidScale=constants::defaultFricPyramidScale, const Eigen::VectorXd &wrenchRatio=Eigen::VectorXd::Zero(0))
 Add markers to GUI. More...
 

Static Public Member Functions

static std::shared_ptr< ContactmakeSharedFromConfig (const mc_rtc::Configuration &mcRtcConfig)
 Make shared pointer from mc_rtc configuration. More...
 

Public Attributes

std::string name_
 Name of contact. More...
 
Eigen::Matrix< double, 6, Eigen::Dynamic > graspMat_
 Grasp matrix. More...
 
Eigen::Matrix< double, 6, Eigen::Dynamic > localGraspMat_
 Local grasp matrix. More...
 
std::shared_ptr< FrictionPyramidfricPyramid_
 Friction pyramid. More...
 
std::vector< VertexWithRidgevertexWithRidgeList_
 List of global vertex with ridges. More...
 
std::optional< sva::ForceVecd > maxWrench_
 Maximum wrench in local frame that can be accepted by this contact. More...
 

Detailed Description

Contact.

Definition at line 40 of file Contact.h.

Constructor & Destructor Documentation

◆ Contact()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW ForceColl::Contact::Contact ( const std::string &  name,
std::optional< sva::ForceVecd >  maxWrench = std::nullopt 
)

Constructor.

Parameters
namename of contact
maxWrenchmaximum wrench in local frame (absolute value) that can be accepted by this contact

Member Function Documentation

◆ addToGUI()

virtual void ForceColl::Contact::addToGUI ( mc_rtc::gui::StateBuilder &  gui,
const std::vector< std::string > &  category,
double  forceScale = constants::defaultForceScale,
double  fricPyramidScale = constants::defaultFricPyramidScale,
const Eigen::VectorXd &  wrenchRatio = Eigen::VectorXd::Zero(0) 
)
virtual

Add markers to GUI.

Parameters
guiGUI
categorycategory of GUI entries
forceScalescale of force markers (set non-positive for no visualization)
fricPyramidScalescale of friction pyramid markers (set non-positive for no visualization)
wrenchRatiowrench ratio of each ridge

Reimplemented in ForceColl::GraspContact, and ForceColl::SurfaceContact.

◆ calcLocalWrench()

sva::ForceVecd ForceColl::Contact::calcLocalWrench ( const Eigen::VectorXd &  wrenchRatio) const

Calculate the local wrench.

Parameters
wrenchRatiowrench ratio of each ridge
Returns
contact wrench in local frame

◆ calcWrench()

sva::ForceVecd ForceColl::Contact::calcWrench ( const Eigen::VectorXd &  wrenchRatio,
const Eigen::Vector3d &  momentOrigin = Eigen::Vector3d::Zero() 
) const

Calculate wrench.

Parameters
wrenchRatiowrench ratio of each ridge
momentOriginmoment origin
Returns
contact wrench

◆ makeSharedFromConfig()

static std::shared_ptr<Contact> ForceColl::Contact::makeSharedFromConfig ( const mc_rtc::Configuration &  mcRtcConfig)
static

Make shared pointer from mc_rtc configuration.

Parameters
mcRtcConfigmc_rtc configuration

◆ ridgeNum()

int ForceColl::Contact::ridgeNum ( ) const
inline

Get the number of ridges.

Definition at line 83 of file Contact.h.

◆ type()

virtual std::string ForceColl::Contact::type ( ) const
pure virtual

◆ updateGlobalVertices()

virtual void ForceColl::Contact::updateGlobalVertices ( const sva::PTransformd &  pose)
pure virtual

Update graspMat_ and vertexWithRidgeList_ according to the input pose.

Implemented in ForceColl::GraspContact, ForceColl::SurfaceContact, and ForceColl::EmptyContact.

Member Data Documentation

◆ fricPyramid_

std::shared_ptr<FrictionPyramid> ForceColl::Contact::fricPyramid_

Friction pyramid.

Definition at line 129 of file Contact.h.

◆ graspMat_

Eigen::Matrix<double, 6, Eigen::Dynamic> ForceColl::Contact::graspMat_

Grasp matrix.

Definition at line 123 of file Contact.h.

◆ localGraspMat_

Eigen::Matrix<double, 6, Eigen::Dynamic> ForceColl::Contact::localGraspMat_

Local grasp matrix.

Definition at line 126 of file Contact.h.

◆ maxWrench_

std::optional<sva::ForceVecd> ForceColl::Contact::maxWrench_

Maximum wrench in local frame that can be accepted by this contact.

Definition at line 135 of file Contact.h.

◆ name_

std::string ForceColl::Contact::name_

Name of contact.

Definition at line 120 of file Contact.h.

◆ vertexWithRidgeList_

std::vector<VertexWithRidge> ForceColl::Contact::vertexWithRidgeList_

List of global vertex with ridges.

Definition at line 132 of file Contact.h.


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