Skip to content

Commit

Permalink
Moved most of the config specific edits to the configuration tutorial.
Browse files Browse the repository at this point in the history
Added a link in the launch tutorial to the moveit_cpp tutorial.
Added the CMakeLists.txt code and expliantions to the moveit_cpp tutorial.
  • Loading branch information
Jakeisthesnake committed Jan 27, 2025
1 parent 699f177 commit 4c4587b
Show file tree
Hide file tree
Showing 4 changed files with 102 additions and 60 deletions.
2 changes: 0 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,6 @@ Below are some links to help with the ports.

## MoveIt Tutorials Source Build

(This section can be skipped if you aren't adding executable code. You don't need to build MoveIt to add an explanation about something.)

Follow the [MoveIt Source Build](https://moveit.ros.org/install-moveit2/source/) instructions to set up a colcon workspace with MoveIt from the source.

Open a command line to your colcon workspace:
Expand Down
48 changes: 47 additions & 1 deletion doc/examples/moveit_cpp/moveitcpp_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -29,4 +29,50 @@ The entire code can be seen :codedir:`here in the MoveIt GitHub project<examples

The Launch File
---------------
The entire launch file is :codedir:`here<examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py>` on GitHub. All the code in this tutorial can be run from the **moveit2_tutorials** package that you have as part of your MoveIt setup.
The entire launch file is :codedir:`here<examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py>` on GitHub.
Notably, the launch file contains the following node

.. code-block:: python
# MoveItCpp demo executable
moveit_cpp_node = Node(
name="moveit_cpp_tutorial",
package="moveit2_tutorials",
executable="moveit_cpp_tutorial",
output="screen",
parameters=[moveit_config.to_dict()],
)
This node contains parameters which are passed to the executable associated with moveit_cpp_tutorial.

The CMakeLists.txt File
-----------------------
During the build process, the CMakeLists.txt file assigns where the launcher will look for the executable.
Below is the CMakeLists.txt file for this tutorial:

.. code-block:: cmake
add_executable(moveit_cpp_tutorial src/moveit_cpp_tutorial.cpp)
target_include_directories(moveit_cpp_tutorial PUBLIC include)
ament_target_dependencies(moveit_cpp_tutorial ${THIS_PACKAGE_INCLUDE_DEPENDS} Boost)
install(TARGETS moveit_cpp_tutorial
DESTINATION lib/${PROJECT_NAME}
)
install(DIRECTORY launch
DESTINATION share/${PROJECT_NAME}
)
install(DIRECTORY config
DESTINATION share/${PROJECT_NAME}
)
``add_executable`` builds the executable named moveit_cpp_tutorial from the source file ``src/moveit_cpp_tutorial.cpp``.

``target_include_directories`` specifies the directories to search for header files during compilation.
``PUBLIC`` makes the include directory available to targets that depend on ``moveit_cpp_tutorial``.

``ament_target_dependencies`` specifies dependencies for the moveit_cpp_tutorial executable.
``${THIS_PACKAGE_INCLUDE_DEPENDS}`` is a variable defined in the ``moveit2_tutorials`` root directory's CMakeLists.txt file, which list common dependencies used in moveit2_tutorials.

``install(TARGET ...)`` and ``install(DIRECTORY ...)`` specify where to put the built executable and directories needed to run your program.

For more details about custom executables, please browse the other examples on this site as well as the ROS documentation.
Original file line number Diff line number Diff line change
Expand Up @@ -167,21 +167,68 @@ or you can include selected sub-components as follows:
Note that the above syntax will automatically look for configuration files that match the default file naming patterns described in this document.
If you have a different naming convention, you can use the functions available in ``MoveItConfigsBuilder`` to directly set file names.
For example, to use a non-default robot description and IK solver file path, and configure planning pipelines:
Using the launch file from :doc:`/doc/tutorials/quickstart_in_rviz/quickstart_in_rviz_tutorial` as an example:

.. code-block:: python
from moveit_configs_utils import MoveItConfigsBuilder
# Define xacro mappings for the robot description file
launch_arguments = {
"robot_ip": "xxx.yyy.zzz.www",
"use_fake_hardware": "true",
"gripper": "robotiq_2f_85",
"dof": "7",
}
# Load the robot configuration
moveit_config = (
MoveItConfigsBuilder("my_robot")
.robot_description(file_path="config/my_robot.urdf.xacro")
.robot_description_kinematics(file_path="config/my_kinematics_solver.yaml")
MoveItConfigsBuilder(
"gen3", package_name="kinova_gen3_7dof_robotiq_2f_85_moveit_config"
)
.robot_description(mappings=launch_arguments)
.trajectory_execution(file_path="config/moveit_controllers.yaml")
.planning_scene_monitor(
publish_robot_description=True, publish_robot_description_semantic=True
)
.planning_pipelines(
pipelines=["ompl", "pilz_industrial_motion_planner"],
default_planning_pipeline="pilz_industrial_motion_planner",
pipelines=["ompl", "stomp", "pilz_industrial_motion_planner"]
)
.to_moveit_configs()
)
``MoveItConfigsBuilder`` (`defined here <https://github.com/moveit/moveit2/blob/main/moveit_configs_utils/moveit_configs_utils/moveit_configs_builder.py>`_) can take a few different types of arguments.

* ``MoveItConfigsBuilder(package_name="package_name")`` will search for a package named "package_name".
* ``MoveItConfigsBuilder("robot_name")`` will search for an explicitly given package name.
Both arguments can be given, in which case the robot name is stored and the package with the explicitly given name will be loaded.
As seen above, ``gen3`` is the robot name, and MoveIt looks for the package ``kinova_gen3_7dof_robotiq_2f_85_moveit_config`` instead of ``gen3_moveit_config``.

``.robot_description`` can optionally take a file path to ``robot_name.urdf`` and/or assign a dictionary of argument mappings that are passed to the robot's urdf.xacro file.
The file path to ``robot_name.urdf`` must be relative to your robot package, so if your robot package is ``/robot_package`` and the urdf (or urdf xacro) file is ``robot_package/config/robot_name.urdf``
you would pass ``.robot_description(filepath="config/robot_name.urdf")``.
If you don't provide a file path, but you do give ``MoveItConfigsBuilder`` a robot name (see above paragraph), MoveIt will look for ``robot_package/config/robot_name.urdf``.

``.trajectory_execution`` loads trajectory execution and MoveIt controller manager's parameters from an optionally provided file path.
If a file path isn't given, MoveIt looks for files in the package's ``config`` folder for files ending with ``controllers.yaml``.

``.planning_scene_monitor`` allows you to set various parameters about what scene information is published and how often is it published.

``.planning_pipelines`` allows to you to list the names of the planners you want available to be used by your robot.
If you opt to not list pipelines, as in ``.planning_pipelines()``, MoveIt will look in the config folder of your package for files that end with "_planning.yaml".
Additionally, if no pipelines are listed, MoveIt will load a set of planners from its own library - this can be disabled adding ``load_all=False`` as an argument to ``.planning_pipelines``.
Listing the planner names specifiies which planners MoveIt should load; again these should be in your config folder.
MoveIt will also pick one of your planners to be the default planner.
If OMPL is one of your planners, it will be the default planner unless you set ``default_planning_pipeline`` to your desired default planner as in

.. code-block:: python
.planning_pipelines(
pipelines=["ompl", "your_favorite_planner"],
default_planning_pipeline="your_favorite_planner",
)
If OMPL is not in your planner list and you don't set a default planner, MoveIt will pick the first planner in the list.

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.
Original file line number Diff line number Diff line change
Expand Up @@ -44,40 +44,6 @@ A handy way to refer to a MoveIt configuration package is to use the ``MoveItCon
.to_moveit_configs()
)
``MoveItConfigsBuilder`` (`defined here <https://github.com/moveit/moveit2/blob/main/moveit_configs_utils/moveit_configs_utils/moveit_configs_builder.py>`_) can take a few different types of arguments.
``MoveItConfigsBuilder(package_name="package_name")`` will search for a package named "package_name".
``MoveItConfigsBuilder("robot_name")`` will search for an explicitly given package name.
Both arguments can be given, in which case the robot name is stored and the package with the explicitly given name will be loaded.
As seen above, ``gen3`` is the robot name, and MoveIt looks for the package ``kinova_gen3_7dof_robotiq_2f_85_moveit_config`` instead of ``gen3_moveit_config``.

``.robot_description`` can optionally take a file path to ``robot_name.urdf`` and/or assign a dictionary of argument mappings that are passed to the robot's urdf.xacro file.
The file path to ``robot_name.urdf`` must be relative to your robot package, so if your robot package is ``/robot_package`` and the urdf (or urdf xacro) file is ``robot_package/config/robot_name.urdf``
you would pass ``.robot_description(filepath="config/robot_name.urdf")``.
If you don't provide a file path, but you do give ``MoveItConfigsBuilder`` a robot name (see above paragraph), MoveIt will look for ``robot_package/config/robot_name.urdf``.

``.trajectory_execution`` loads trajectory execution and MoveIt controller manager's parameters from an optionally provided file path.
If a file path isn't given, MoveIt looks for files in the package's ``config`` folder for files ending with ``controllers.yaml``.

``.planning_scene_monitor`` allows you to set various parameters about what scene information is published and how often is it published.

``.planning_pipelines`` allows to you to list the names of the planners you want available to be used by your robot.
If you opt to not list pipelines, as in ``.planning_pipelines()``, MoveIt will look in the config folder of your package for files that end with "_planning.yaml".
Additionally, if no pipelines are listed, MoveIt will load a set of planners from its own library - this can be disabled adding ``load_all=False`` as an argument to ``.planning_pipelines``.
Listing the planner names specifiies which planners MoveIt should load; again these should be in your config folder.
MoveIt will also pick one of your planners to be the default planner.
If OMPL is one of your planners, it will be the default planner unless you set ``default_planning_pipeline`` to your desired default planner as in

.. code-block:: python
.planning_pipelines(
pipelines=["ompl", "your_favorite_planner"],
default_planning_pipeline="your_favorite_planner",
)
If OMPL is not in your planner list and you don't set a default planner, MoveIt will pick the first planner in the list.



Launching Move Group
--------------------

Expand Down Expand Up @@ -249,22 +215,7 @@ Finally, we can tell our launch file to actually launch everything we described
]
)
Launching a custom .cpp file
Launching a custom executable
----------------------------

While not part of the Getting Started tutorial, another common node to launch is one that executes a custom .cpp file:

.. code-block:: python
moveit_cpp_node = Node(
name="custom_program",
package="custom_program_package",
executable="custom_program",
output="screen",
parameters=[your,
parameters,
here],
)
where ``moveit_cpp_node_parameters`` is a list of parameters for that node. See Ros2 documentation for more information on launching .cpp files.
Additionally, the tutorials on this site provide more examples on how to create programs to customize MoveIt's capabilities for your project.
Later on these tutorials (:doc:`/doc/examples/moveit_cpp/moveit_cpp_tutorial`), you will learn how to create and launch a custom executable.

0 comments on commit 4c4587b

Please sign in to comment.