PlanningScene.attach_collision_mesh_to_robot_end_effector

PlanningScene.attach_collision_mesh_to_robot_end_effector(collision_mesh, scale=False, group=None)[source]

Attaches a collision mesh to the robot’s end-effector.

Parameters
  • collision_mesh (CollisionMesh) – The collision mesh to attach to robot’s end effector.

  • scale (bool, optional) – If True, the mesh will be copied and scaled according to the robot’s scale factor.

  • group (str) – The planning group with the end effector we want to attach the mesh to. Defaults to the robot’s main planning group.

Returns

None

Examples

>>> scene = PlanningScene(robot)
>>> mesh = Mesh.from_stl(compas_fab.get('planning_scene/cone.stl'))
>>> cm = CollisionMesh(mesh, 'tip')
>>> group = robot.main_group_name
>>> scene.attach_collision_mesh_to_robot_end_effector(cm, group=group)      # attach to ee
>>> scene.remove_attached_collision_mesh('tip')                             # now detach