.. _ik: IK Solver Configuration =============================== The following is an example to compute the ``ee_pose_convertor`` for Panda robot: 1. First, configure the IK config except for ``ee_pose_convertor``. .. code-block:: yaml robot: urdf: ${oc.env:MANISKILL_ASSETS}/robots/panda/panda_v2.urdf fix_root_link: false cut: root: panda_hand cuts: [panda_hand_tcp, panda_leftfinger, panda_rightfinger] ik: ee_pose_convertor: [q: [1, 0, 0, 0]] # a default pose, TODO: compute this ee_name: ["panda_hand"] # end-effector name fix_joint_indices: [] n_retry: 0 max_iterations: 100 threshold: 1e-3 use_projected_ik: false # true mod_2pi: false # true 2. View "PickCube-v1" environment with Panda robot: .. code-block:: bash python3 tools.py view configs/examples/maniskill_panda/pick_cube.yaml This will launch a built-in SAPIEN GUI. 3. In the GUI, click ``Scene`` → ``Entities`` → ``panda_hand`` (the end-effector name), then find ``Show Coordinate Frame`` under ``Selection``. Click it to show the local frame for the end-effector link. .. figure:: assets/GUI_screenshot.png :width: 800px :align: center steps to show end-effector local frame in SAPIEN GUI 4. Compare the local frame for controller frame and the end-effector frame. Align the controller frame to the end-effector frame with desired controlling direction, and find the difference between the two local frames. .. figure:: assets/align_local_pose.png :width: 500px :align: center 5. Analyze the axis relationships between the two local frames. In this example: - end-effector X axis aligns with controller **X** axis. - end-effector Y axis align with controller **-Y** axis. - end-effector Z axis aligns with controller **-Z** axis. 6. Compute the quaternion to convert the controller frame to the end-effector frame using: .. code-block:: bash python3 tools.py convert "x -y -z" 7. Replace the ``ee_pose_convertor`` in the IK config with the computed quaternion. And the final IK config should look like this: .. code-block:: yaml robot: urdf: ${oc.env:MANISKILL_ASSETS}/robots/panda/panda_v2.urdf fix_root_link: false cut: root: panda_hand cuts: [panda_hand_tcp, panda_leftfinger, panda_rightfinger] ik: ee_pose_convertor: [q: [0, 1, 0, 0]] ee_name: ["panda_hand"] # end-effector name fix_joint_indices: [] n_retry: 0 max_iterations: 100 threshold: 1e-3 use_projected_ik: false # true mod_2pi: false # true Reference Coordinate Frames ----------------------------------------------- The following figures show the controller & hand local frames for reference. .. figure:: assets/controller.jpg :width: 600px :align: center Controller local frame .. figure:: assets/hand.jpg :width: 600px :align: center Hand local frame