Drake
Drake C++ Documentation
AllegroHandMotionState Class Reference

Detailed Description

Detecting the state of the fingers: whether the joints are moving, or reached the destination, or got stuck by external collisions in the midway.

The class uses only the hand status from the MBP as the input, and calculate the state according to the position, velocity, and command position of each joint. The class also contains two commonly used pre-set joint state for opening the hand and closing the hand for grasping.

#include <drake/examples/allegro_hand/allegro_common.h>

Public Member Functions

 AllegroHandMotionState ()
 
void Update (const lcmt_allegro_status &allegro_state_msg)
 Update the states of the joints and fingers upon receiving the new message about hand staties. More...
 
Eigen::Vector4d FingerGraspJointPosition (int finger_index) const
 Pre-set joint positions for grasping objects and open hands. More...
 
Eigen::Vector4d FingerOpenJointPosition (int finger_index) const
 
bool IsFingerStuck (int finger_index) const
 Returns true when the finger is stuck, which means the joints on the finger stops moving or back driving, regardless of it having reached the target position or not. More...
 
bool IsAllFingersStuck () const
 
bool IsAnyHighFingersStuck () const
 Return whether any of the fingers, other than the thumb, is stuck. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 AllegroHandMotionState (const AllegroHandMotionState &)=default
 
AllegroHandMotionStateoperator= (const AllegroHandMotionState &)=default
 
 AllegroHandMotionState (AllegroHandMotionState &&)=default
 
AllegroHandMotionStateoperator= (AllegroHandMotionState &&)=default
 

Constructor & Destructor Documentation

◆ AllegroHandMotionState() [1/3]

◆ AllegroHandMotionState() [2/3]

◆ AllegroHandMotionState() [3/3]

Member Function Documentation

◆ FingerGraspJointPosition()

Eigen::Vector4d FingerGraspJointPosition ( int  finger_index) const

Pre-set joint positions for grasping objects and open hands.

Parameters
finger_indexthe index of the fingers whose joint values are in request.

◆ FingerOpenJointPosition()

Eigen::Vector4d FingerOpenJointPosition ( int  finger_index) const

◆ IsAllFingersStuck()

bool IsAllFingersStuck ( ) const

◆ IsAnyHighFingersStuck()

bool IsAnyHighFingersStuck ( ) const

Return whether any of the fingers, other than the thumb, is stuck.

◆ IsFingerStuck()

bool IsFingerStuck ( int  finger_index) const

Returns true when the finger is stuck, which means the joints on the finger stops moving or back driving, regardless of it having reached the target position or not.

◆ operator=() [1/2]

AllegroHandMotionState& operator= ( AllegroHandMotionState &&  )
default

◆ operator=() [2/2]

AllegroHandMotionState& operator= ( const AllegroHandMotionState )
default

◆ Update()

void Update ( const lcmt_allegro_status &  allegro_state_msg)

Update the states of the joints and fingers upon receiving the new message about hand staties.


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