Grasp Plug-in

Grasp Plug-in provides two main functions; one is the grasp planning for multi-fingered hands and the other is the basic functions commonly used by other plug-ins. In the following, we will mainly explain the grasp planning function of this plug-in.

Basic Information

Planner Bar

By using the bar entitled "=Planner=", the grasping posture can be planned.
PlannerBar.png
For more detailed information, please refer Planner Bar Help .

Tutorials

Motion Planning

The Grasp Plugin is for obtaining an appropriate position for the gripper for the purpose of grasping and setting and does not take into consideration how the entire arm will be moved. Use the PRM plugin to formulate a motion plan for the arm that does not interfere with the surrounding environment. Refer to PRM plug-in for details.

Grasp Planning Algorithm

This plug-in uses a grasp planning algorithm where the bounding box models are used for both the hand grasping region and the object model. By using this plug-in, we can construct several grasping styles for multi-fingered hand such as the 3 fingered fingertip grasp, the 4 fingered fingertip grasp, and the enveloping grasp. Here, we call the bounding box expressing the grasping region as the Grasping Rectangular Convex (GRC). Also, we call the bounding box of the object model as the Obect Convex Polygon (OCP). By considering the geometrical relation between the GRC and the OCP, we can determine the approximate position/orientation of the palm. Then the final grasping posture is determined by using the random sampling of the palm position.
Also, we use the fast method for checking the force closure by using the ellipsoidal approximation of the friction cone. Here, since we also prepare the conventional method of force closure, you can use it. For more detailed information on the grasp planning algorithm, please see the references.

References

[1]Kensuke Harada, Kenji Kaneko, and Fumio Kanehiro, Fast Grasp Planning for Hand/Arm Systems Based on Convex Model, 2008 IEEE International Conference on Robotics and Automation, pp. 1162-1168, 2008.
[2]T. Tsuji, K. Harada, and K. Kaneko, Easy and Fast Evaluation of Grasp Stability by using Ellipsoidal Approximation of Friction Cone, Proc. of 2009 IEEE/RSJ Int. Conf. on Intelligent Robots and Systems,pp.1830-1837、2009.
[4]T. Tsuji, K. Harada, K. Kaneko, F. Kanehiro, and K. Maruyama, Grasp Planning for a Multifingered Hand with a Humanoid Robot, Journal of Robotics and Mechatronics, Vol.22 No.2, pp. 230-238, 2010.

Methodology for introducing a new robot model in graspPlugin

This section describes how to prepare for the grasp planning stage when a new robot is introduced. HRP2JRL is used as an example of a robot model.

(1) Edit the yaml file

Edit the file “graspPlugin/RobotModels/HRP2JRL/HRP2.yaml” in a similar manner to that shown below. The meaning of each entry is explained on the right, after the “%” sign.

 graspPluginSetting:
    name: HRP2 %Name of the Robot
    base: CHEST_JOINT1 %Base link used when IK is solved
    palm: RARM_JOINT5 %Wrist link used when IK is solved
    fingerEnds:    [ RHAND_JOINT1, RHAND_JOINT4 ] %Finger-tip links
    prehensionList: [ prehension ] %File with reference postures for grasping (prehension.pos, prehension.prm), Multiple reference postures can be specified.
    armStandardPose: [0, 0, 0, -1.57, 0, 0] %Reference posture of the arm when IK is solved by iterative calculations(The Joint angle from the base to palm)
    fingerOpenPose: [0.78, -0.78, 0.78, -0.78, 0.78, -0.78] %Pose with the fingers opened to the maximum possible extent.
    interlink:    [ [ RARM_JOINT6, 1.0 , RHAND_JOINT0, -1.0, RHAND_JOINT1, 1.0 ],[RHAND_JOINT2, -1.0, RHAND_JOINT3, 1.0, RHAND_JOINT4, -1.0]]%Interlocking link
    GrasplotPluginDir: Plugin % Name of the directory that contains the program which solves a specific ID.
    

The interlink definition is very important here. The HRPJ2RL Robot possesses two hands and six links and moves by interlocking links. This entry defines the aforementioned interlocking.

(2) Edit the PRM file

Next, the “prehension.prm” and “prehension.pos files” are specified. These files are stored in the “graspPlugin/RobotModels/HRP2JRL/data” path.

Note:
The “prehension.prm” file contains descriptors that hold parameters related to the grasp types (3-fingered fingertip grasp, 4-fingered fingertip grasp, enveloping grasp, etc.) and the “prehension.pos” file contains the standard postures while grasping in any of the above grasp types.

(2-1) prehension.prm

The entries between the [START] and [END] of this file, for example, are filled as shown below.
    
    Reference_Motion prehension
    Finger0Contact    0 1 0
    Finger0Comp        0 0 0
    Finger0Close    0.01 -0.01 0.01 
    Finger1Contact    0 1 0
    Finger1Comp        0 0 0
    Finger1Close    -0.01 0.01 -0.01  
    GRCdes_Position    0.0 0.0 -0.19
    GRCmax_Position    0.0 0.0 -0.30
    GRCmin_Position 0.0 0.0 -0.19
    GRCdes_Rpy    -1.57 0 0 
    GRCmax_Rpy    -1.57 0 0 
    GRCmin_Rpy    -1.57 0 0 
    GRCdes_Edges     0.05 0.05 0.05
    GRCmax_Edges     0.30 0.30 0.10
    GRCmin_Edges     0.01 0.01 0.01 
    Max_Load     1.0
    Min_Load     0

Each entry is explained below.
Finger[i]Contact
Defines which i-th link of the finger contacts the object. In the case of the H2P2JRL model, only the second link of both the 0th and 1st fingers would make contact with the object.
Finger[i]Comp
Defines which joint should be used to compensate for the link position while bringing the j-th link (of the i-th finger) into contact with the object. In the case of the H2P2JRL model, the 0th joint is generally used.
GRC[max,des,min]_Position, GRC[max,des,min]_Rpy, GRC[max,dex,min]_Edges
The rectangular cuboid that specifies the grasp type. This defines the position, posture, and side length of the GRC (Grasping Rectangular Convex). The figures below show examples of GRCmax and GRCdes. It should be noted that GRCmax specifies the range for “random sampling” of the object positions. GRCdes specifies the desired grasp type. Furthermore, the hand approaches the object in the GRC coordinate system along the y axis, and so the posture should be decided accordingly.
[Max, Min]_Load
Specifies the maximum and minimum weight of the grasp object in kg.

(2-2)prehension.pos

For example, the entries in this file are as shown below.
0 0.78 -0.78 0.78 -0.78 0.78 -0.78
The first 0 can be any arbitrary number, but the numbers after that specify the finger joint angles in the same order as specified in the VRML.

With this, the setup for using the Grasp Plug-in is complete.

GRCmax2.jpg GRCmax
GRCdes2.jpg GRCdes