# which arm to be used for grasping string arm_name
# a list of possible desired poses of the object once it's been placed geometry_msgs/PoseStamped[] place_locations
# the grasp that has been executed on this object Grasp grasp
# how far the retreat should ideally be away from the place location float32 desired_retreat_distance
# the min distance between the retreat and the place location that must actually be feasible # for the place not to be rejected float32 min_retreat_distance
# how the place location should be approached # the frame_id that this lift is specified in MUST be either the robot_frame # or the gripper_frame specified in your hand description file GripperTranslation approach
# the name that the target object has in the collision map # can be left empty if no name is available string collision_object_name
# the name that the support surface (e.g. table) has in the collision map # can be left empty if no name is available string collision_support_surface_name
# whether collisions between the gripper and the support surface should be acceptable # during move from pre-place to place and during retreat. Collisions when moving to the # pre-place location are still not allowed even if this is set to true. bool allow_gripper_support_collision
# whether reactive placing based on tactile sensors should be used bool use_reactive_place
# how much the object should be padded by when deciding if the grasp # location is freasible or not float64 place_padding
# OPTIONAL (These will not have to be filled out most of the time) # constraints to be imposed on every point in the motion of the arm motion_planning_msgs/Constraints path_constraints
# OPTIONAL (These will not have to be filled out most of the time) # additional collision operations to be used for every arm movement performed # during placing. Note that these will be added on top of (and thus overide) other # collision operations that the grasping pipeline deems necessary. Should be used # with care and only if special behaviors are desired. motion_planning_msgs/OrderedCollisionOperations additional_collision_operations
# OPTIONAL (These will not have to be filled out most of the time) # additional link paddings to be used for every arm movement performed # during placing. Note that these will be added on top of (and thus overide) other # link paddings that the grasping pipeline deems necessary. Should be used # with care and only if special behaviors are desired. motion_planning_msgs/LinkPadding[] additional_link_padding