|
| 1 | +MoveIt Configuration |
| 2 | +================================== |
| 3 | + |
| 4 | +The recommended way of configuring MoveIt for your robot is by creating a colcon package containing the MoveIt Configuration. |
| 5 | + |
| 6 | +Suppose you would like to create a configuration package for some robot named ``my_robot``. |
| 7 | +To do this, you can create a colcon package named ``my_robot_moveit_config``, whose structure is as follows: |
| 8 | + |
| 9 | +.. code-block:: |
| 10 | +
|
| 11 | + my_robot_moveit_config |
| 12 | + config/ |
| 13 | + kinematics.yaml |
| 14 | + joint_limits.yaml |
| 15 | + *_planning.yaml |
| 16 | + moveit_controllers.yaml |
| 17 | + moveit_cpp.yaml |
| 18 | + sensors_3d.yaml |
| 19 | + ... |
| 20 | + launch/ |
| 21 | + .setup_assistant |
| 22 | + CMakeLists.txt |
| 23 | + package.xml |
| 24 | +
|
| 25 | +You can create such a package manually, or use the :doc:`MoveIt Setup Assistant </doc/examples/setup_assistant/setup_assistant_tutorial>` to automatically generate it given a robot description file (URDF or xacro). |
| 26 | + |
| 27 | +Refer to the `moveit_resources <https://github.com/ros-planning/moveit_resources/tree/ros2>`_ repository for working examples of MoveIt configuration packages. |
| 28 | + |
| 29 | + |
| 30 | +Configuration Files Overview |
| 31 | +---------------------------- |
| 32 | + |
| 33 | +The ``config/`` folder of a MoveIt configuration package contains several files that describe parameters for various capabilities of MoveIt. |
| 34 | + |
| 35 | +Note that several of these files are optional depending on the functionality required at runtime. |
| 36 | + |
| 37 | +Robot Description |
| 38 | +^^^^^^^^^^^^^^^^^ |
| 39 | + |
| 40 | +This is the most important piece of information in a MoveIt configuration package. |
| 41 | +There must be a URDF and SRDF file present in this folder to describe the robot kinematics, planning groups, collision rules, and more. |
| 42 | +To learn more about these files, refer to the :doc:`URDF/SRDF Overview </doc/examples/urdf_srdf/urdf_srdf_tutorial>`. |
| 43 | + |
| 44 | +Joint Limits |
| 45 | +^^^^^^^^^^^^ |
| 46 | + |
| 47 | +The URDF file specification allows setting joint position and velocity limits. |
| 48 | +However, you may want to define different joint limits for motion planning with MoveIt without modifying the underlying robot description file. |
| 49 | +Furthermore, some features in MoveIt use additional types of joint limits, such as acceleration and jerk limits, which cannot be specified in URDF. |
| 50 | + |
| 51 | +The default location of this file is in ``config/joint_limits.yaml``. |
| 52 | + |
| 53 | +Here is an example snippet of a joint limits file for a simple robot with two joints: |
| 54 | + |
| 55 | +.. code-block:: yaml |
| 56 | +
|
| 57 | + joint_limits: |
| 58 | + joint1: |
| 59 | + has_velocity_limits: true |
| 60 | + max_velocity: 2.0 |
| 61 | + has_acceleration_limits: true |
| 62 | + max_acceleration: 4.0 |
| 63 | + has_jerk_limits: false |
| 64 | + panda_joint2: |
| 65 | + has_velocity_limits: true |
| 66 | + max_velocity: 1.5 |
| 67 | + has_acceleration_limits: true |
| 68 | + max_acceleration: 3.0 |
| 69 | + has_jerk_limits: false |
| 70 | +
|
| 71 | +Inverse Kinematics (IK) Solver |
| 72 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 73 | + |
| 74 | +Many motion planning applications in MoveIt require solving inverse kinematics. |
| 75 | + |
| 76 | +Both the IK solver plugin used and its parameters are configured through a file whose default location is ``config/kinematics.yaml``. |
| 77 | + |
| 78 | +For more information, refer to :doc:`Kinematics Configuration </doc/examples/kinematics_configuration/kinematics_configuration_tutorial>`. |
| 79 | + |
| 80 | +Motion Planning Configuration |
| 81 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 82 | + |
| 83 | +For each type of motion planner plugin available in MoveIt, there is a corresponding ``config/*_planning.yaml`` file that describes its configuration. |
| 84 | +For example, a robot that can use both :doc:`OMPL </doc/examples/ompl_interface/ompl_interface_tutorial>` and :doc:`Pilz Industrial Motion Planner </doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner>` will have the following folder structure: |
| 85 | + |
| 86 | +.. code-block:: |
| 87 | +
|
| 88 | + my_robot_moveit_config |
| 89 | + config/ |
| 90 | + ompl_planning.yaml |
| 91 | + pilz_industrial_motion_planner_planning.yaml |
| 92 | + ... |
| 93 | + ... |
| 94 | +
|
| 95 | +By default, all parameter files that match this ``config/*_planning.yaml`` pattern will be loaded. |
| 96 | +If OMPL is configured as a planning pipeline, that will be the default; otherwise, it will be the first pipeline in the list. |
| 97 | + |
| 98 | +To learn more about the contents of the individual planning configuration files, refer to the configuration documentation for those planners. |
| 99 | + |
| 100 | +Trajectory Execution Configuration |
| 101 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 102 | + |
| 103 | +MoveIt typically publishes manipulator motion commands to a `JointTrajectoryController <https://github.com/ros-controls/ros2_controllers/tree/master/joint_trajectory_controller>`_. |
| 104 | +To learn more, refer to the :doc:`Low Level Controllers </doc/examples/controller_configuration/controller_configuration_tutorial>` section. |
| 105 | + |
| 106 | +The default location for trajectory execution information is in ``config/moveit_controllers.yaml``. |
| 107 | + |
| 108 | +MoveItCpp Configuration |
| 109 | +^^^^^^^^^^^^^^^^^^^^^^^ |
| 110 | + |
| 111 | +If you are using :doc:`MoveItCpp </doc/examples/moveit_cpp/moveitcpp_tutorial>`, you can define a file with all the necessary parameters. |
| 112 | + |
| 113 | +The default location of this file is in ``config/moveit_cpp.yaml``. |
| 114 | + |
| 115 | +3D Perception Configuration |
| 116 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 117 | + |
| 118 | +If you are using a perception sensor capable of generating 3D point clouds for motion planning, you can configure those settings for MoveIt. |
| 119 | +For more information, refer to the :doc:`Perception Pipeline Tutorial </doc/examples/perception_pipeline/perception_pipeline_tutorial>`. |
| 120 | + |
| 121 | +The default location of this file is in ``config/sensors_3d.yaml``. |
| 122 | + |
| 123 | +Loading Configuration Parameters into Launch Files |
| 124 | +-------------------------------------------------- |
| 125 | + |
| 126 | +To easily load parameters from MoveIt configuration packages for use in your ROS 2 launch files, MoveIt provides a ``MoveItConfigsBuilder`` utility. |
| 127 | +To load the configuration parameters from your ``my_robot_moveit_config`` package: |
| 128 | + |
| 129 | +.. code-block:: python |
| 130 | +
|
| 131 | + from moveit_configs_utils import MoveItConfigsBuilder |
| 132 | +
|
| 133 | + moveit_config = ( |
| 134 | + MoveItConfigsBuilder("my_robot") |
| 135 | + .to_moveit_configs() |
| 136 | + ) |
| 137 | +
|
| 138 | +Then, you can either use the complete set of configuration parameters when launching a node: |
| 139 | + |
| 140 | +.. code-block:: python |
| 141 | +
|
| 142 | + from launch_ros.actions import Node |
| 143 | +
|
| 144 | + my_node = Node( |
| 145 | + package="my_package", |
| 146 | + executable="my_executable", |
| 147 | + parameters=[moveit_config.to_dict()], |
| 148 | + ) |
| 149 | +
|
| 150 | +or you can include selected sub-components as follows: |
| 151 | + |
| 152 | +.. code-block:: python |
| 153 | +
|
| 154 | + from launch_ros.actions import Node |
| 155 | +
|
| 156 | + my_node = Node( |
| 157 | + package="my_package", |
| 158 | + executable="my_executable", |
| 159 | + parameters=[ |
| 160 | + moveit_config.robot_description, |
| 161 | + moveit_config.robot_description_semantic, |
| 162 | + moveit_config.robot_description_kinematics, |
| 163 | + ], |
| 164 | + ) |
| 165 | +
|
| 166 | +Note that the above syntax will automatically look for configuration files that match the default file naming patterns described in this document. |
| 167 | +If you have a different naming convention, you can use the functions available in ``MoveItConfigsBuilder`` to directly set file names. |
| 168 | +For example, to use a non-default robot description and IK solver file path, and configure planning pipelines: |
| 169 | + |
| 170 | +.. code-block:: python |
| 171 | +
|
| 172 | + from moveit_configs_utils import MoveItConfigsBuilder |
| 173 | +
|
| 174 | + moveit_config = ( |
| 175 | + MoveItConfigsBuilder("my_robot") |
| 176 | + .robot_description(file_path="config/my_robot.urdf.xacro") |
| 177 | + .robot_description_kinematics(file_path="config/my_kinematics_solver.yaml") |
| 178 | + .planning_pipelines( |
| 179 | + pipelines=["ompl", "pilz_industrial_motion_planner"], |
| 180 | + default_planning_pipeline="pilz_industrial_motion_planner", |
| 181 | + ) |
| 182 | + .to_moveit_configs() |
| 183 | + ) |
| 184 | +
|
| 185 | +Now that you have read this page, you should be able to better understand the launch files available throughout the MoveIt 2 tutorials, and when encountering other MoveIt configuration packages in the wild. |
0 commit comments