pybullet_planning.primitives.grasp_gen.get_side_cylinder_grasps

pybullet_planning.primitives.grasp_gen.get_side_cylinder_grasps(body, tool_pose=((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0)), body_pose=((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0)), reverse_grasp=False, safety_margin_length=0.0)[source]

generate side grasp using the body’s bounding cylinder.

The generated grasp should be used as: world_from_body = world_from_gripper * grasp

The image below shows the default gripper axis convention.

../../_images/cylinder_grasp_convention.png
Parameters
  • body (int) – body id for the body being grasped

  • tool_pose (Pose, optional) – additional default_ee_from_customized_ee, by default unit_pose()

  • body_pose (Pose, optional) – the body’s current pose, used for computing bounding box, by default unit_pose()

  • reverse_grasp (bool, optional) – generate flipped gripper for pi-symmetry around the gripper’s z axis, by default False

  • safety_margin_length (float, optional) – safety margin along the gripper’s y axis, i.e. the top_offset shown in the picture, by default 0.0

Yields

Pose – gripper_from_body