From 7a26c1e41f52f5d8b46b395e62d5cd82c5bcd824 Mon Sep 17 00:00:00 2001 From: Sebastian Castro Date: Thu, 20 Apr 2023 21:19:37 -0400 Subject: [PATCH 1/7] Add MoveIt Configuration Tutorial --- doc/examples/examples.rst | 3 +- .../moveit_configuration_tutorial.rst | 186 ++++++++++++++++++ 2 files changed, 188 insertions(+), 1 deletion(-) create mode 100644 doc/examples/moveit_configuration/moveit_configuration_tutorial.rst diff --git a/doc/examples/examples.rst b/doc/examples/examples.rst index 293dea1d05..addc7652ef 100644 --- a/doc/examples/examples.rst +++ b/doc/examples/examples.rst @@ -69,6 +69,7 @@ Configuration .. toctree:: :maxdepth: 1 + moveit_configuration/moveit_configuration_tutorial kinematics_configuration/kinematics_configuration_tutorial custom_constraint_samplers/custom_constraint_samplers_tutorial ompl_interface/ompl_interface_tutorial @@ -76,7 +77,7 @@ Configuration stomp_planner/stomp_planner_tutorial trajopt_planner/trajopt_planner_tutorial pilz_industrial_motion_planner/pilz_industrial_motion_planner - planning_adapters/planning_adapters_tutorial.rst + planning_adapters/planning_adapters_tutorial persistent_scenes_and_states/persistent_scenes_and_states Miscellaneous diff --git a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst new file mode 100644 index 0000000000..11f356c670 --- /dev/null +++ b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst @@ -0,0 +1,186 @@ +MoveIt Configuration +================================== + +The recommended way of configuring MoveIt for your robot is by creating a Colcon package containing the MoveIt Configuration. + +Suppose you would like to create a configuration package for some robot named ``my_robot``. +To do this, you can create a Colcon package named ``my_robot_moveit_config``, whose structure is as follows: + +.. code-block:: + + my_robot_moveit_config + config/ + kinematics.yaml + joint_limits.yaml + *_planning.yaml + moveit_controllers.yaml + moveit_cpp.yaml + sensors_3d.yaml + ... + launch/ + .setup_assistant + CMakeLists.txt + package.xml + +You can create such a package manually, or use the :doc:`MoveIt Setup Assistant ` to automatically generate it given a robot description file (URDF or xacro). + +Refer to the `moveit_resources `_ repository for working examples of MoveIt configuration packages. + + +Configuration Files Overview +---------------------------- + +The ``config/`` folder of a MoveIt configuration package contains several files that describe parameters for various capabilities of MoveIt. + +Note that several of these files are optional depending on the functionality required at runtime. + +Robot Description +^^^^^^^^^^^^^^^^^ + +This is the most important piece of information in a MoveIt configuration package. +There must be a URDF and SRDF file present in this folder to describe the robot kinematics, planning groups, collision rules, and more. +To learn more about these files, refer to the :doc:`URDF/SRDF Overview `. + +Joint Limits +^^^^^^^^^^^^ + +The URDF file specification allows setting joint position and velocity limits. +However, you may want to define different joint limits for motion planning with MoveIt without modifying the underlying robot description file. +Furthermore, some features in MoveIt use additional types of joint limits, such as acceleration and jerk limits, which cannot be specified in URDF. + +The default location of this file is in ``config/joint_limits.yaml``. + +Here is an example snippet of a joint limits file for a simple robot with two joints: + +.. code-block:: yaml + + joint_limits: + joint1: + has_velocity_limits: true + max_velocity: 2.0 + has_acceleration_limits: true + max_acceleration: 4.0 + has_jerk_limits: false + panda_joint2: + has_velocity_limits: true + max_velocity: 1.5 + has_acceleration_limits: true + max_acceleration: 3.0 + has_jerk_limits: false + +Inverse Kinematics (IK) Solver +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Many motion planning applications in MoveIt require solving inverse kinematics. +For more information, refer to :doc:`Kinematics Configuration `. + +The default location of this file is in ``config/kinematics.yaml``. + +Motion Planning Configuration +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +For each type of motion planner available in MoveIt, there is a corresponding ``config/*_planning.yaml`` file that describes its configuration. +For example, a robot that uses both :doc:`OMPL ` and :doc:`Pilz Industrial Motion Planner ` will have the following folder structure: + +.. code-block:: + + my_robot_moveit_config + config/ + ompl_planning.yaml + pilz_industrial_motion_planner_planning.yaml + ... + ... + +By default, all parameter files that match this ``config/_*planning.yaml`` pattern will be loaded. +If OMPL is configured as a planning pipeline, that will be the default; otherwise, it will be the first pipeline in the list. + +If you want to load a specific subset of motion planners, you can additionally create a ``config/planning_pipelines.yaml`` file to explicitly list the planning pipelines to load, as well as the default pipeline. + +To learn more about the contents of the individual planning configuration files, refer to the configuration documentation for those planners. + +Trajectory Execution Configuration +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +MoveIt typically publishes manipulator motion commands to a `JointTrajectoryController `_. +To learn more, refer to the :doc:`Low Level Controllers ` section. + +The default location for trajectory execution information is in ``config/moveit_controllers.yaml``. + +MoveItCpp Configuration +^^^^^^^^^^^^^^^^^^^^^^^ + +If you are using :doc:`MoveItCpp `, you can define a file with all the necessary parameters. + +The default location of this file is in ``config/moveit_cpp.yaml``. + +3D Perception Configuration +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +If you are using a perception sensor capable of generating 3D point clouds for motion planning, you can configure those settings for MoveIt. +For more information, refer to the :doc:`Perception Pipeline Tutorial `. + +The default location of this file is in ``config/sensors_3d.yaml``. + + + +Loading Configuration Parameters into Launch Files +-------------------------------------------------- + +To easily load parameters from MoveIt configuration packages for use in your ROS 2 launch files, MoveIt provides a ``MoveItConfigsBuilder`` utility. + + +To load the configuration parameters from your ``my_robot_moveit_config`` package: + +.. code-block:: python + + from moveit_configs_utils import MoveItConfigsBuilder + + moveit_config = ( + MoveItConfigsBuilder("my_robot") + .to_moveit_configs() + ) + +Then, you can either use the complete set of configuration parameters when launching a node: + +.. code-block:: python + + from launch_ros.actions import Node + + my_node = Node( + package="my_package", + executable="my_executable", + parameters=[moveit_config.to_dict()], + ) + +or you can include selected sub-components as follows: + +.. code-block:: python + + from launch_ros.actions import Node + + my_node = Node( + package="my_package", + executable="my_executable", + parameters=[ + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + ], + ) + +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: + +.. code-block:: python + + from moveit_configs_utils import MoveItConfigsBuilder + + moveit_config = ( + MoveItConfigsBuilder("my_robot") + .robot_description(file_path="config/my_robot.urdf.xacro") + .robot_description_kinematics(file_path="config/my_kinematics_solver.yaml") + .to_moveit_configs() + ) + +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. From 61a92eacc2581a45097e42130176b86e32bc02f4 Mon Sep 17 00:00:00 2001 From: Sebastian Castro Date: Thu, 20 Apr 2023 21:30:36 -0400 Subject: [PATCH 2/7] Fix doc references --- .../moveit_configuration_tutorial.rst | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst index 11f356c670..af89cfd95b 100644 --- a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst +++ b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst @@ -72,7 +72,7 @@ Inverse Kinematics (IK) Solver ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Many motion planning applications in MoveIt require solving inverse kinematics. -For more information, refer to :doc:`Kinematics Configuration `. +For more information, refer to :doc:`Kinematics Configuration `. The default location of this file is in ``config/kinematics.yaml``. @@ -80,7 +80,7 @@ Motion Planning Configuration ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ For each type of motion planner available in MoveIt, there is a corresponding ``config/*_planning.yaml`` file that describes its configuration. -For example, a robot that uses both :doc:`OMPL ` and :doc:`Pilz Industrial Motion Planner ` will have the following folder structure: +For example, a robot that uses both :doc:`OMPL ` and :doc:`Pilz Industrial Motion Planner ` will have the following folder structure: .. code-block:: @@ -102,14 +102,14 @@ Trajectory Execution Configuration ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ MoveIt typically publishes manipulator motion commands to a `JointTrajectoryController `_. -To learn more, refer to the :doc:`Low Level Controllers ` section. +To learn more, refer to the :doc:`Low Level Controllers ` section. The default location for trajectory execution information is in ``config/moveit_controllers.yaml``. MoveItCpp Configuration ^^^^^^^^^^^^^^^^^^^^^^^ -If you are using :doc:`MoveItCpp `, you can define a file with all the necessary parameters. +If you are using :doc:`MoveItCpp `, you can define a file with all the necessary parameters. The default location of this file is in ``config/moveit_cpp.yaml``. @@ -117,7 +117,7 @@ The default location of this file is in ``config/moveit_cpp.yaml``. ^^^^^^^^^^^^^^^^^^^^^^^^^^^ If you are using a perception sensor capable of generating 3D point clouds for motion planning, you can configure those settings for MoveIt. -For more information, refer to the :doc:`Perception Pipeline Tutorial `. +For more information, refer to the :doc:`Perception Pipeline Tutorial `. The default location of this file is in ``config/sensors_3d.yaml``. From 2143bbfd03c637f9f64f283d1cebddf1b31a40f5 Mon Sep 17 00:00:00 2001 From: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Date: Fri, 21 Apr 2023 08:26:32 -0400 Subject: [PATCH 3/7] Apply suggestions from code review Co-authored-by: Sebastian Jahr --- .../moveit_configuration_tutorial.rst | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst index af89cfd95b..4c693dc427 100644 --- a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst +++ b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst @@ -1,7 +1,7 @@ MoveIt Configuration ================================== -The recommended way of configuring MoveIt for your robot is by creating a Colcon package containing the MoveIt Configuration. +The recommended way of configuring MoveIt for your robot is by creating a colcon package containing the MoveIt Configuration. Suppose you would like to create a configuration package for some robot named ``my_robot``. To do this, you can create a Colcon package named ``my_robot_moveit_config``, whose structure is as follows: @@ -79,8 +79,8 @@ The default location of this file is in ``config/kinematics.yaml``. Motion Planning Configuration ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -For each type of motion planner available in MoveIt, there is a corresponding ``config/*_planning.yaml`` file that describes its configuration. -For example, a robot that uses both :doc:`OMPL ` and :doc:`Pilz Industrial Motion Planner ` will have the following folder structure: +For each type of motion planner plugin available in MoveIt, there is a corresponding ``config/*_planning.yaml`` file that describes its configuration. +For example, a robot that can use both :doc:`OMPL ` and :doc:`Pilz Industrial Motion Planner ` will have the following folder structure: .. code-block:: @@ -121,14 +121,10 @@ For more information, refer to the :doc:`Perception Pipeline Tutorial Date: Fri, 21 Apr 2023 08:28:40 -0400 Subject: [PATCH 4/7] Add clarifying note about kinematics.yaml --- .../moveit_configuration/moveit_configuration_tutorial.rst | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst index 4c693dc427..9f1421f577 100644 --- a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst +++ b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst @@ -72,9 +72,10 @@ Inverse Kinematics (IK) Solver ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Many motion planning applications in MoveIt require solving inverse kinematics. -For more information, refer to :doc:`Kinematics Configuration `. -The default location of this file is in ``config/kinematics.yaml``. +Both the IK solver plugin used and its parameters are configured through a file whose default location is ``config/kinematics.yaml``. + +For more information, refer to :doc:`Kinematics Configuration `. Motion Planning Configuration ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ From 54bbcc3684676b6bf6c06ff025d63b9f38e3b2b9 Mon Sep 17 00:00:00 2001 From: Sebastian Castro Date: Fri, 21 Apr 2023 09:40:01 -0400 Subject: [PATCH 5/7] Fix planning pipelines documentation --- .../moveit_configuration_tutorial.rst | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst index 9f1421f577..c9304be982 100644 --- a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst +++ b/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst @@ -4,7 +4,7 @@ MoveIt Configuration The recommended way of configuring MoveIt for your robot is by creating a colcon package containing the MoveIt Configuration. Suppose you would like to create a configuration package for some robot named ``my_robot``. -To do this, you can create a Colcon package named ``my_robot_moveit_config``, whose structure is as follows: +To do this, you can create a colcon package named ``my_robot_moveit_config``, whose structure is as follows: .. code-block:: @@ -95,8 +95,6 @@ For example, a robot that can use both :doc:`OMPL Date: Fri, 21 Apr 2023 09:54:46 -0400 Subject: [PATCH 6/7] Move updated examples to how-to guides and clean up how-to TOC --- CMakeLists.txt | 6 ++--- doc/examples/examples.rst | 3 --- doc/how_to_guides/how_to_guides.rst | 23 +++++++++++++++--- .../moveit_configuration_tutorial.rst | 2 +- .../CMakeLists.txt | 0 .../data/kitchen_panda_db.sqlite | Bin .../launch/persistent_scenes_demo.launch.py | 0 .../persistent_scenes_and_states.rst | 0 .../rviz_connect.png | Bin .../CMakeLists.txt | 0 .../blend_radius.png | Bin .../launch/pilz_mtc.launch.py | 0 .../pilz_industrial_motion_planner.rst | 16 ++++++------ .../pilz_industrial_motion_planner/ptp.png | Bin .../rviz_planner.png | Bin .../src/pilz_move_group.cpp | 0 .../src/pilz_mtc.cpp | 0 17 files changed, 31 insertions(+), 19 deletions(-) rename doc/{examples => how_to_guides}/moveit_configuration/moveit_configuration_tutorial.rst (98%) rename doc/{examples => how_to_guides}/persistent_scenes_and_states/CMakeLists.txt (100%) rename doc/{examples => how_to_guides}/persistent_scenes_and_states/data/kitchen_panda_db.sqlite (100%) rename doc/{examples => how_to_guides}/persistent_scenes_and_states/launch/persistent_scenes_demo.launch.py (100%) rename doc/{examples => how_to_guides}/persistent_scenes_and_states/persistent_scenes_and_states.rst (100%) rename doc/{examples => how_to_guides}/persistent_scenes_and_states/rviz_connect.png (100%) rename doc/{examples => how_to_guides}/pilz_industrial_motion_planner/CMakeLists.txt (100%) rename doc/{examples => how_to_guides}/pilz_industrial_motion_planner/blend_radius.png (100%) rename doc/{examples => how_to_guides}/pilz_industrial_motion_planner/launch/pilz_mtc.launch.py (100%) rename doc/{examples => how_to_guides}/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst (97%) rename doc/{examples => how_to_guides}/pilz_industrial_motion_planner/ptp.png (100%) rename doc/{examples => how_to_guides}/pilz_industrial_motion_planner/rviz_planner.png (100%) rename doc/{examples => how_to_guides}/pilz_industrial_motion_planner/src/pilz_move_group.cpp (100%) rename doc/{examples => how_to_guides}/pilz_industrial_motion_planner/src/pilz_mtc.cpp (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index fd1a34ad09..bdd27afe71 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -58,14 +58,14 @@ add_subdirectory(doc/examples/motion_planning_pipeline) add_subdirectory(doc/examples/motion_planning_python_api) add_subdirectory(doc/examples/move_group_interface) add_subdirectory(doc/examples/moveit_cpp) -add_subdirectory(doc/examples/persistent_scenes_and_states) -add_subdirectory(doc/examples/pilz_industrial_motion_planner) add_subdirectory(doc/examples/planning_scene_ros_api) add_subdirectory(doc/examples/planning_scene) add_subdirectory(doc/examples/realtime_servo) add_subdirectory(doc/examples/robot_model_and_robot_state) -add_subdirectory(doc/how_to_guides/using_ompl_constrained_planning) add_subdirectory(doc/how_to_guides/parallel_planning) +add_subdirectory(doc/how_to_guides/persistent_scenes_and_states) +add_subdirectory(doc/how_to_guides/pilz_industrial_motion_planner) +add_subdirectory(doc/how_to_guides/using_ompl_constrained_planning) add_subdirectory(doc/tutorials/pick_and_place_with_moveit_task_constructor) add_subdirectory(doc/tutorials/quickstart_in_rviz) diff --git a/doc/examples/examples.rst b/doc/examples/examples.rst index addc7652ef..a047306bd9 100644 --- a/doc/examples/examples.rst +++ b/doc/examples/examples.rst @@ -69,16 +69,13 @@ Configuration .. toctree:: :maxdepth: 1 - moveit_configuration/moveit_configuration_tutorial kinematics_configuration/kinematics_configuration_tutorial custom_constraint_samplers/custom_constraint_samplers_tutorial ompl_interface/ompl_interface_tutorial chomp_planner/chomp_planner_tutorial stomp_planner/stomp_planner_tutorial trajopt_planner/trajopt_planner_tutorial - pilz_industrial_motion_planner/pilz_industrial_motion_planner planning_adapters/planning_adapters_tutorial - persistent_scenes_and_states/persistent_scenes_and_states Miscellaneous ---------------------------- diff --git a/doc/how_to_guides/how_to_guides.rst b/doc/how_to_guides/how_to_guides.rst index 98a15e747a..31ae1d627a 100644 --- a/doc/how_to_guides/how_to_guides.rst +++ b/doc/how_to_guides/how_to_guides.rst @@ -3,13 +3,28 @@ How-To Guides These how-to guides will help you quickly solve specific problems using MoveIt. +For more information, refer to :doc:`/doc/how_to_guides/how_to_guide`. + +Configuring and Using MoveIt +--------------------------- + .. toctree:: :maxdepth: 1 - how_to_guide - how_to_generate_api_doxygen_locally - how_to_setup_docker_containers_in_ubuntu - how_to_write_doxygen + moveit_configuration/moveit_configuration_tutorial + pilz_industrial_motion_planner/pilz_industrial_motion_planner using_ompl_constrained_planning/ompl_constrained_planning parallel_planning/parallel_planning_tutorial controller_teleoperation/controller_teleoperation + persistent_scenes_and_states/persistent_scenes_and_states + +Developing and Documenting MoveIt +--------------------------------- + +.. toctree:: + :maxdepth: 1 + + how_to_generate_api_doxygen_locally + how_to_setup_docker_containers_in_ubuntu + how_to_write_doxygen + diff --git a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst b/doc/how_to_guides/moveit_configuration/moveit_configuration_tutorial.rst similarity index 98% rename from doc/examples/moveit_configuration/moveit_configuration_tutorial.rst rename to doc/how_to_guides/moveit_configuration/moveit_configuration_tutorial.rst index c9304be982..e2ac68b729 100644 --- a/doc/examples/moveit_configuration/moveit_configuration_tutorial.rst +++ b/doc/how_to_guides/moveit_configuration/moveit_configuration_tutorial.rst @@ -81,7 +81,7 @@ Motion Planning Configuration ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ For each type of motion planner plugin available in MoveIt, there is a corresponding ``config/*_planning.yaml`` file that describes its configuration. -For example, a robot that can use both :doc:`OMPL ` and :doc:`Pilz Industrial Motion Planner ` will have the following folder structure: +For example, a robot that can use both :doc:`OMPL ` and :doc:`Pilz Industrial Motion Planner ` will have the following folder structure: .. code-block:: diff --git a/doc/examples/persistent_scenes_and_states/CMakeLists.txt b/doc/how_to_guides/persistent_scenes_and_states/CMakeLists.txt similarity index 100% rename from doc/examples/persistent_scenes_and_states/CMakeLists.txt rename to doc/how_to_guides/persistent_scenes_and_states/CMakeLists.txt diff --git a/doc/examples/persistent_scenes_and_states/data/kitchen_panda_db.sqlite b/doc/how_to_guides/persistent_scenes_and_states/data/kitchen_panda_db.sqlite similarity index 100% rename from doc/examples/persistent_scenes_and_states/data/kitchen_panda_db.sqlite rename to doc/how_to_guides/persistent_scenes_and_states/data/kitchen_panda_db.sqlite diff --git a/doc/examples/persistent_scenes_and_states/launch/persistent_scenes_demo.launch.py b/doc/how_to_guides/persistent_scenes_and_states/launch/persistent_scenes_demo.launch.py similarity index 100% rename from doc/examples/persistent_scenes_and_states/launch/persistent_scenes_demo.launch.py rename to doc/how_to_guides/persistent_scenes_and_states/launch/persistent_scenes_demo.launch.py diff --git a/doc/examples/persistent_scenes_and_states/persistent_scenes_and_states.rst b/doc/how_to_guides/persistent_scenes_and_states/persistent_scenes_and_states.rst similarity index 100% rename from doc/examples/persistent_scenes_and_states/persistent_scenes_and_states.rst rename to doc/how_to_guides/persistent_scenes_and_states/persistent_scenes_and_states.rst diff --git a/doc/examples/persistent_scenes_and_states/rviz_connect.png b/doc/how_to_guides/persistent_scenes_and_states/rviz_connect.png similarity index 100% rename from doc/examples/persistent_scenes_and_states/rviz_connect.png rename to doc/how_to_guides/persistent_scenes_and_states/rviz_connect.png diff --git a/doc/examples/pilz_industrial_motion_planner/CMakeLists.txt b/doc/how_to_guides/pilz_industrial_motion_planner/CMakeLists.txt similarity index 100% rename from doc/examples/pilz_industrial_motion_planner/CMakeLists.txt rename to doc/how_to_guides/pilz_industrial_motion_planner/CMakeLists.txt diff --git a/doc/examples/pilz_industrial_motion_planner/blend_radius.png b/doc/how_to_guides/pilz_industrial_motion_planner/blend_radius.png similarity index 100% rename from doc/examples/pilz_industrial_motion_planner/blend_radius.png rename to doc/how_to_guides/pilz_industrial_motion_planner/blend_radius.png diff --git a/doc/examples/pilz_industrial_motion_planner/launch/pilz_mtc.launch.py b/doc/how_to_guides/pilz_industrial_motion_planner/launch/pilz_mtc.launch.py similarity index 100% rename from doc/examples/pilz_industrial_motion_planner/launch/pilz_mtc.launch.py rename to doc/how_to_guides/pilz_industrial_motion_planner/launch/pilz_mtc.launch.py diff --git a/doc/examples/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst similarity index 97% rename from doc/examples/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst rename to doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst index 84e78a0e0f..03b0f7c7d4 100644 --- a/doc/examples/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst +++ b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst @@ -275,7 +275,7 @@ you can interact with the planner through the RViz MotionPlanning panel. :alt: rviz figure To use the planner through the MoveGroup Interface, refer to -:codedir:`the MoveGroup Interface C++ example `. +:codedir:`the MoveGroup Interface C++ example `. To run this, execute the following commands in separate Terminals: :: @@ -285,7 +285,7 @@ To run this, execute the following commands in separate Terminals: To use the planner using MoveIt Task Constructor, refer to -:codedir:`the MoveIt Task Constructor C++ example `. +:codedir:`the MoveIt Task Constructor C++ example `. To run this, execute the following commands in separate Terminals: :: @@ -340,7 +340,7 @@ To verify the limits were set correctly, you can check the parameters for your Sequence of multiple segments -============================= +----------------------------- To concatenate multiple trajectories and plan the trajectory at once, you can use the sequence capability. This reduces the planning overhead @@ -354,7 +354,7 @@ non of the commands in the sequence are executed. multiple groups (e.g. "Manipulator", "Gripper") User interface sequence capability ----------------------------------- +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A specialized MoveIt functionality known as the :moveit_codedir:`command list manager` @@ -375,7 +375,7 @@ Implementation details are available :moveit_codedir:`as PDF`. Restrictions for ``MotionSequenceRequest`` -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - Only the first goal may have a start state. Following trajectories start at the previous goal. @@ -384,7 +384,7 @@ Restrictions for ``MotionSequenceRequest`` than the distance between the goals. Action interface -~~~~~~~~~~~~~~~~ +^^^^^^^^^^^^^^^^ In analogy to the ``MoveGroup`` action interface, the user can plan and execute a ``moveit_msgs::MotionSequenceRequest`` through the action server @@ -397,12 +397,12 @@ constraints of an individual ``moveit_msgs::msg::MotionPlanRequest`` are already satisfied but the ``MoveGroupSequenceAction`` capability doesn't implement such a check to allow moving on a circular or comparable path. -See the ``pilz_robot_programming`` package for an `ROS1 python script +See the ``pilz_robot_programming`` package for a `ROS 1 Python script `_ that shows how to use the capability. Service interface -~~~~~~~~~~~~~~~~~ +^^^^^^^^^^^^^^^^^ The service ``plan_sequence_path`` allows the user to generate a joint trajectory for a ``moveit_msgs::msg::MotionSequenceRequest``. diff --git a/doc/examples/pilz_industrial_motion_planner/ptp.png b/doc/how_to_guides/pilz_industrial_motion_planner/ptp.png similarity index 100% rename from doc/examples/pilz_industrial_motion_planner/ptp.png rename to doc/how_to_guides/pilz_industrial_motion_planner/ptp.png diff --git a/doc/examples/pilz_industrial_motion_planner/rviz_planner.png b/doc/how_to_guides/pilz_industrial_motion_planner/rviz_planner.png similarity index 100% rename from doc/examples/pilz_industrial_motion_planner/rviz_planner.png rename to doc/how_to_guides/pilz_industrial_motion_planner/rviz_planner.png diff --git a/doc/examples/pilz_industrial_motion_planner/src/pilz_move_group.cpp b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp similarity index 100% rename from doc/examples/pilz_industrial_motion_planner/src/pilz_move_group.cpp rename to doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp diff --git a/doc/examples/pilz_industrial_motion_planner/src/pilz_mtc.cpp b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_mtc.cpp similarity index 100% rename from doc/examples/pilz_industrial_motion_planner/src/pilz_mtc.cpp rename to doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_mtc.cpp From 514cac925e75087f9d56b828f68ea472c6d98e74 Mon Sep 17 00:00:00 2001 From: Sebastian Castro Date: Fri, 21 Apr 2023 10:03:38 -0400 Subject: [PATCH 7/7] Formatting fixes --- doc/how_to_guides/how_to_guides.rst | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/doc/how_to_guides/how_to_guides.rst b/doc/how_to_guides/how_to_guides.rst index 31ae1d627a..eebe7825f4 100644 --- a/doc/how_to_guides/how_to_guides.rst +++ b/doc/how_to_guides/how_to_guides.rst @@ -6,7 +6,7 @@ These how-to guides will help you quickly solve specific problems using MoveIt. For more information, refer to :doc:`/doc/how_to_guides/how_to_guide`. Configuring and Using MoveIt ---------------------------- +---------------------------- .. toctree:: :maxdepth: 1 @@ -27,4 +27,3 @@ Developing and Documenting MoveIt how_to_generate_api_doxygen_locally how_to_setup_docker_containers_in_ubuntu how_to_write_doxygen -