pybullet_planning.interfaces.kinematics.sample_tool_ik

pybullet_planning.interfaces.kinematics.sample_tool_ik(ik_fn, robot, ik_joints, world_from_tcp, base_link, ik_tool_link_from_tcp=None, closest_only=False, get_all=False, **kwargs)[source]

sample ik joints for a given tcp pose in the world frame

Parameters
  • ik_fn (function handle) – get_ik(point, rot) : list of jt solutions point = [x,y,z] rot = 3x3 rotational matrix as a row-major list

  • robot (pybullet robot)

  • ik_joint (list of int) – a list of pybullet joint index that is registered for IK/FK can be obtained by e.g.: ik_joints = joints_from_names(robot, ik_joint_names)

  • base_link (int) – robot base link index, can be obtained from link_from_name(robot, base_link_name)

  • world_from_tcp (pybullet pose) – tcp pose in the world frame

  • ik_tool_link_from_tcp (pybullet pose) – tcp pose in ik tool link’s frame, optional, defaults to None

  • get_all (bool) – get all ik sol computed

  • **kwargs (optional arguments) – for solution selection, nearby_conf=True to select the one that’s closest to current conf in pybullet env

Returns

a list of 6-list – computed IK solutions that satisfy joint limits