diff --git a/config_robot/panda_grasp_data.yaml b/config_robot/panda_grasp_data.yaml index 31c3097..9879b5d 100644 --- a/config_robot/panda_grasp_data.yaml +++ b/config_robot/panda_grasp_data.yaml @@ -1,33 +1,42 @@ base_link: 'world' # ===================================================== -# Note: these parameters are copied from Robotiq gripper without tweaking hand: end_effector_name: 'hand' # ee group name end_effector_type: 'finger' # 'finger' or 'suction' + # ===================================================== + # Grasping parameters + # TODO: move to other file + # x/y translation and angle orientation grasp resolution parameters used for sampling grasp candidates grasp_resolution : 0.05 # meter angle_resolution : 90 # degrees - # min/max values of the grasp depth range in meter. - # This should fit to the distance from finger tip to inner palm or the suction cup stroke - grasp_max_depth : 0.035 - grasp_min_depth : 0.01 - # grasp_depth_resolution is the discretization distance in meter used for sampling the grasp depth value. - # Idealy this should be a small fraction of the depth range (i.e. 0.005). - # If the value exceeds the depth distance range grasp_max_depth is used by default. - grasp_depth_resolution : 1.0 - # A grasp motion is composed of three linear paths: approach, retreat, lift # The values below define the desired distances of each path. # Length of approach path (this is in addition to the grasp_max_depth) approach_distance_desired: 0.05 # approach path (in addition to grasp_max_depth) retreat_distance_desired: 0.05 # retreat path (in addition to grasp_max_depth) - lift_distance_desired: 0.01 # lift path (used as MINIMUM safety distance from surface) + lift_distance_desired: 0.1 # lift path (used as MINIMUM safety distance from surface) # minimum padding on each side of the object on approach grasp_padding_on_approach: 0.005 # meter + # grasp_depth_resolution is the discretization distance in meter used for sampling the grasp depth value. + # Idealy this should be a small fraction of the depth range (i.e. 0.005). + # If the value exceeds the depth distance range grasp_max_depth is used by default. + grasp_depth_resolution : 1.0 + + # ===================================================== + # Hand parameters + + # min/max values of the grasp depth range in meter. + # Peferrably, the grasp_max_depth is always used, but sometimes no grasp is available at that depth + # so it can fall back to a 'less deep' grasp if necessary + # This should fit to the distance from finger tip to inner palm or the suction cup stroke + grasp_max_depth : 0.035 + grasp_min_depth : 0.01 + # Distance from the eef mount to the palm of end effector [x, y, z, r, p, y] # z-axis pointing toward object to grasp # x-axis perp. to movement of grippers @@ -41,7 +50,8 @@ hand: pregrasp_posture : [0.04] # open position grasp_posture : [0.0] # close position - # Target durations in seconds for reaching pregrasp and grasp positions in end effector motions + # Target durations, in seconds, for reaching pregrasp and grasp positions in end effector motions + # This is an estimate of how fast your end effector operates pregrasp_time_from_start : 0.0 grasp_time_from_start : 0.0