.. _motion_planning_getting_started: Getting Started ================== .. highlight:: python Installation -------------------------------------- We recommend use `mplib `_ for motion planning with SAPIEN. ``mplib`` is a lightweight python package that includes common functionalities for motion planning. You can use mplib to plan a collision-free trajectory for a robot, calculate inverse kinematics, and take point cloud observation as an environment model. Unlike `MoveIt `_, ``mplib`` is decoupled from ROS, and it's easy to set up and use with simple python APIs. Please use pip to install ``mplib``: .. code:: bash pip install mplib Supported Python versions: 3.6, 3.7, 3.8, 3.9 Supported operating system: Ubuntu 18.04+ .. note:: ``mplib`` is a standalone package and can be used independently without SAPIEN. Planner Configuration -------------------------------------- In :ref:`basic_robot`, we learned how to load a robot in SAPIEN: .. literalinclude:: ../../../../examples/motion_planning/demo.py :dedent: 0 :lines: 33-36 To use ``mplib``, we need to first set up a planner for the robot: .. literalinclude:: ../../../../examples/motion_planning/demo.py :dedent: 0 :lines: 74-84 - The URDF file describes the robot, while the `SRDF `_ file complements the URDF and specifies additional information for motion planning. For example, ``mplib`` loads the ``disable_collisions`` pairs in SRDF to ignore collisions between certain pairs of links. Currently, SRDF files are generated by ``MoveIt Setup Assistant``. In the future, we may provide other tools for generating SRDF files. - To align the link order and joint order between SAPIEN and ``mplib``, we need to provide ``user_link_names`` and ``user_joint_names``. After that, ``mplib`` can tell which joints the ``qpos`` vector (from SAPIEN) is referring to. Please note that we only care about the active joints (i.e., revolute and prismatic joints) and ignore the fixed joints. - ``move_group`` specifies the target link [1]_ for which we may specify target poses to reach. The end-effector of an agent is typically specified as the ``move_group``. After specifying the ``move_group``, ``mplib`` only focuses on those active joints along the path from the root link to the ``move_group``, since other joints doesn't affect the pose of the ``move_group``. For example, for our ``panda`` robot arm (7 DoF), the end-effector is ``panda_hand``. Only the first seven active joints affect the pose of ``panda_hand``, while the last two finger joints don't. - For safety, the robot cannot move arbitrarily fast. ``joint_vel_limits`` and ``joint_acc_limits`` specify the maximum joint velocity and maximum joint acceleration constraints for the active joints along the path from the root link to the ``move_group``. ``mplib`` takes the constraints into account when solving the time-optimal path parameterization. After setting up the planner, we can use it to solve many motion planning tasks. .. [1] ``mplib`` currently only supports a single link as ``move_group``.