Getting Started#

Installation#

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:

pip install mplib

Supported Python versions: 3.6+

Supported operating system: Ubuntu 18.04+

Planner Configuration#

To use mplib, we need to first set up a planner for the robot with the following constructor:

    def __init__(
        self,
        urdf: str | Path,
        move_group: str,
        *,
        srdf: Optional[str | Path] = None,
        new_package_keyword: str = "",
        use_convex: bool = False,
        user_link_names: Sequence[str] = [],
        user_joint_names: Sequence[str] = [],
        joint_vel_limits: Optional[Sequence[float] | np.ndarray] = None,
        joint_acc_limits: Optional[Sequence[float] | np.ndarray] = None,
        objects: list[FCLObject] = [],  # noqa: B006
        verbose: bool = False,
    ):
  • 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 such as adjacent joints. Currently, SRDF files are generated by MoveIt Setup Assistant. In the future, we may provide other tools for generating SRDF files.

  • To specify the link order and joint order, one can provide user_link_names and user_joint_names. By default, the joints and links are in the order they are loaded. However, if you are using a simulation library such as sapien, you might need to change this. 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. By default, mplib uses 1.0m/s and 1.0m/s^2 as the default joint velocity and acceleration limits.

After setting up the planner, we can use it to solve many motion planning tasks.