libmove3d  3.13.0
Public Member Functions | Public Attributes
gpHand_properties Class Reference

#include <graspPlanning.h>

List of all members.

Public Member Functions

int initialize (gpHand_type hand_type)
struct robinitialize ()
int setThand_wrist (p3d_matrix4 T)
int setArmType (gpArm_type arm_type)
int draw (p3d_matrix4 pose)

Public Attributes

gpHand_type type
unsigned int nb_fingers
unsigned int nb_dofs
 number of active DOFs of the hand
double fingertip_radius
 radius of the fingertips or approximative half-width of the distal phalanges
p3d_matrix4 Tgrasp_frame_hand
p3d_matrix4 Thand_wrist
double edgeAngleThreshold
 values used to discard contacts close to sharp edges as unstable
double edgeDistanceThreshold
unsigned int nb_positions
 discretization parameters that will be given to the grasp generation function:
unsigned int nb_directions
unsigned int nb_rotations
unsigned int max_nb_grasp_frames
std::vector< double > qmin
 vector of the minimal and maximal bounds on joint parameters
std::vector< double > qmax
std::vector< double > qrest
 vector of a "rest" configuration of the hand
std::vector< double > qopen
 vector to reach from a given grasp configuration in order to find an pregrasp configuration
double fingertip_distance
double min_opening
double max_opening
double min_opening_jnt_value
double max_opening_jnt_value
double joint_fingertip_distance
double length_thumbBase
double length_proxPha
double length_midPha
double length_distPha
p3d_matrix4 Twrist_finger [4]
 transformation matrices wrist frame (= hand's reference frame) -> finger base frame
std::vector< class gpSphereworkspace
 joint limits of the four fingers: maybe deprecated (check this)

Detailed Description

Class containing information about a given hand (type, dimensions). Some fields will be used or not depending on the kind of hand.


Member Function Documentation

int gpHand_properties::draw ( p3d_matrix4  pose)

Draws different things that allow to visualize the dimension settings in a gpHand_properties class by comparing the displayed things to the display of the Move3D model. Must be used in an OpenGL context.

Parameters:
posethe frame the things will be drawn in relatively to. Use the robot's wrist frame for instance.
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpHand_properties::initialize ( gpHand_type  hand_type)

Initializes the geometric info for the selected hand type. NB: The convention for the wrist frame of the SAHands is (view from top, with direct frames): Z Z ^ ^ | | | | || || || || || || || || || / / \ \ || || || ||_||_|| / / \ \ ||_||_|| | / ---> Y Y <--- \ | |__LEFT__/ |__RIGHT_|

p3d_rob * gpHand_properties::initialize ( ) [read]

Initializes a gpHand_properties variable. The function explores all the existing robots to find those with the specific names defined in graspPlanning.h The hand type is deduced from these names.

Returns:
pointer to the hand robot, NULL otherwise
int gpHand_properties::setArmType ( gpArm_type  arm_type)

Sets the arm the hand is supposed to be mounted on. It is used to set Thand_wrist to one of some predefined values. Default values are set when calling initialize() (for now they correspond to how the gripper or the SAHand are mounted on the PA-10).

Parameters:
arm_typethe desired arm type
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpHand_properties::setThand_wrist ( p3d_matrix4  T)

Sets the matrix used to compute the arm wrist position from a given hand frame. It depends on how the hand is linked to the arm and on the convention used for the arm's kinematics. Default values are set when calling initialize() (for now they correspond to how the gripper or the SAHand are mounted on the PA-10).

Parameters:
Tthe new value of Thand_wrist
Returns:
GP_OK in case of success, GP_ERROR otherwise

Member Data Documentation

values used to discard contacts close to sharp edges as unstable

if the angle at an edge is sharper than this value (in radians), the edge is considered as sharp

a contact is considered as close to an edge if the distance to this edge is smaller than this value

distance between the two first fingers (the ones on the same U-shaped body)

distance from the gripper's joint to the middle of the fingerpads

SAHAND/////////////////////////////////////////////////// lengths of the thumb's first phalanx and of the proximal, middle et distal phalanges:

minimal distance between the gripper's jaws (maximal opening)

the value of the gripper joint's DOF when the gripper opening is maximal

minimal distance between the gripper's jaws (minimal opening)

the value of the gripper joint's DOF when the gripper opening is minimal

matrix that will give the hand position from a given grasp frame. It depends on the convention used for the hand robot model. grasp_frame*Tgrasp_frame_hand --> hand_frame

matrix that will give the arm wrist position from a given hand frame. It depends on how the hand is linked to the arm and on the convention used for the arm's kinematics. hand_frame*Thand_wrist --> arm's wrist frame

joint limits of the four fingers: maybe deprecated (check this)

approximation of the finger workspace by a set of spheres:


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines