Skip to content

Commit

Permalink
Merge branch 'ros-planning:main' into main
Browse files Browse the repository at this point in the history
  • Loading branch information
mosfet80 authored Dec 28, 2023
2 parents 37e5b7e + ea6d999 commit c354f30
Show file tree
Hide file tree
Showing 31 changed files with 88 additions and 36 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/deploy.yml
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ jobs:
cp -f api.html build/html/main/doc/api/python_api/ # restore artifact html
- name: Upload pages artifact
uses: actions/upload-pages-artifact@v2
uses: actions/upload-pages-artifact@v3
if: github.repository_owner == 'ros-planning'
with:
path: build/html
Expand All @@ -161,4 +161,4 @@ jobs:
steps:
- name: Deploy to GitHub Pages
id: deployment
uses: actions/deploy-pages@v3
uses: actions/deploy-pages@v4
6 changes: 6 additions & 0 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,12 @@ repos:

- repo: local
hooks:
- id: misspelled-moveit
name: misspelled-moveit
description: MoveIt should be spelled exactly as MoveIt
language: pygrep
entry: Moveit\W|MoveIt!|Moveit2|MoveIt2
exclude: .pre-commit-config.yaml
- id: clang-format
name: clang-format
description: Format files with ClangFormat.
Expand Down
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ endforeach()
include_directories(${THIS_PACKAGE_INCLUDE_DIRS})

# add_subdirectory(doc/examples/bullet_collision_checker)
# add_subdirectory(doc/examples/collision_environments)
add_subdirectory(doc/examples/collision_environments)
# add_subdirectory(doc/examples/controller_configuration)
# add_subdirectory(doc/examples/creating_moveit_plugins/lerp_motion_planner)
# add_subdirectory(doc/examples/interactivity)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ MoveIt typically publishes manipulator motion commands to a `JointTrajectoryCont

#. A launch file. This launch file must load the :code:`moveit_controllers` yaml file and specify the :code:`moveit_simple_controller_manager/MoveItSimpleControllerManager`. After these yaml files are loaded, they are passed as parameters to the Move Group node. `Example Move Group launch file <https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config/launch/demo.launch.py>`_.

#. Launch the corresponding :code:`ros2_control` JointTrajectoryControllers. This is separate from the MoveIt2 ecosystem. `Example ros2_control launching <https://github.com/ros-controls/ros2_control_demos>`_. Each JointTrajectoryController provides an action interface. Given the yaml file above, MoveIt automatically connects to this action interface.
#. Launch the corresponding :code:`ros2_control` JointTrajectoryControllers. This is separate from the MoveIt 2 ecosystem. `Example ros2_control launching <https://github.com/ros-controls/ros2_control_demos>`_. Each JointTrajectoryController provides an action interface. Given the yaml file above, MoveIt automatically connects to this action interface.

#. Note: it is not required to use :code:`ros2_control` for your robot. You could write a proprietary action interface. In practice, 99% of users choose :code:`ros2_control`.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@

#include <pluginlib/class_loader.h>

// MoveIt!
// MoveIt
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/planning_interface/planning_interface.h>
#include <moveit/planning_scene/planning_scene.h>
Expand Down
2 changes: 1 addition & 1 deletion doc/examples/dual_arms/dual_arms_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ Dual Arms with MoveIt

There are quite a few configuration steps to control two or more manipulators with MoveIt. Luckily it has gotten easier over time. Here, an example is provided and we list all the changes needed to go from 1 robot to X robots.

The launch and configuration files in this example are available :codedir:`here. <examples/dual_arms>`
The launch and configuration files in this example are available :moveit_resources_codedir:`here. <dual_arm_panda_moveit_config>`

Running the Demo
----------------
Expand Down
4 changes: 2 additions & 2 deletions doc/examples/hybrid_planning/hybrid_planning_tutorial.rst
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
Hybrid Planning
===============

In this section, you will learn how to use Moveit 2's *Hybrid Planning* feature.
In this section, you will learn how to use MoveIt 2's *Hybrid Planning* feature.

Hybrid Planning enables you to (re)plan and execute robot motions online with MoveIt 2 and to add more planning logic into your robot's motion planning pipeline.

Expand Down Expand Up @@ -90,7 +90,7 @@ To include the Hybrid Planning Architecture into you project you need to add a *
Customizing the Hybrid Planning Architecture
--------------------------------------------
As the rest of Moveit 2, the *Hybrid Planning Architecture* is designed to be highly customizable while also offering the possibility to easily re-use existing solutions. Each of the architecture's components is a ROS 2 node and can be completely replaced by your own custom ROS 2 node as long as it offers the API required by the other nodes. Each component's runtime behavior is defined by plugins. This section focuses on the customization of the *Hybrid Planning Architecture* by implementing your own plugins.
As the rest of MoveIt 2, the *Hybrid Planning Architecture* is designed to be highly customizable while also offering the possibility to easily re-use existing solutions. Each of the architecture's components is a ROS 2 node and can be completely replaced by your own custom ROS 2 node as long as it offers the API required by the other nodes. Each component's runtime behavior is defined by plugins. This section focuses on the customization of the *Hybrid Planning Architecture* by implementing your own plugins.

Global and Local Motion Planning
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ The code for this tutorial can be found `here <https://github.com/peterdavidfaga

Getting Started
---------------
To complete this tutorial, you must have set up a colcon workspace that includes MoveIt2 and its corresponding tutorials. An excellent outline on how to set up such a workspace is provided in the :doc:`Getting Started Guide </doc/tutorials/getting_started/getting_started>`.
To complete this tutorial, you must have set up a colcon workspace that includes MoveIt 2 and its corresponding tutorials. An excellent outline on how to set up such a workspace is provided in the :doc:`Getting Started Guide </doc/tutorials/getting_started/getting_started>`.

Once you have set up your workspace, you can execute the code for this tutorial by running the following command (the servo section of this tutorial requires a PS4 Dualshock, if you don't have one consider setting this parameter to false): ::

Expand Down Expand Up @@ -140,7 +140,10 @@ Once our MoveIt configuration is defined we start the following set of nodes:
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
"source": [
"# Introduction\n",
"\n",
"Welcome to this tutorial on using jupyter notebooks with Moveit 2. A great benefit of being able to interact with MoveIt via a Python notebook is the ability to rapidly prototype code. We hope you find this interface intuitive and that you gain value from using MoveIt via Python notebooks.\n",
"Welcome to this tutorial on using jupyter notebooks with MoveIt 2. A great benefit of being able to interact with MoveIt via a Python notebook is the ability to rapidly prototype code. We hope you find this interface intuitive and that you gain value from using MoveIt via Python notebooks.\n",
"\n",
"In this tutorial we will cover the following: \n",
"\n",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="log",
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
5 changes: 4 additions & 1 deletion doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,10 @@ def generate_launch_description():
ros2_control_node = launch_ros.actions.Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="screen",
)

Expand Down
2 changes: 1 addition & 1 deletion doc/examples/realtime_servo/realtime_servo_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ If you haven't already done so, make sure you've completed the steps in :doc:`Ge
Design overview
---------------

Moveit Servo consists of two main parts: The core implementation ``Servo`` which provides a C++ interface, and the ``ServoNode`` which
MoveIt Servo consists of two main parts: The core implementation ``Servo`` which provides a C++ interface, and the ``ServoNode`` which
wraps the C++ interface and provides a ROS interface.The configuration of Servo is done through ROS parameters specified in :moveit_codedir:`servo_parameters.yaml <moveit_ros/moveit_servo/config/servo_parameters.yaml>`

In addition to the servoing capability, MoveIt Servo has some convenient features such as:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ MoveIt can support different algorithms for post-processing a kinematic trajecto

* :moveit_codedir:`Time-optimal Trajectory Generation<moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp>`

Time-optimal Trajectory Generation (TOTG) was introduced in PRs `#809 <https://github.com/ros-planning/moveit/pull/809>`_ and `#1365 <https://github.com/ros-planning/moveit/pull/1365>`_. It produces trajectories with very smooth and continuous velocity profiles. The method is based on fitting path segments to the original trajectory and then sampling new waypoints from the optimized path. This is different from strict time parameterization methods as resulting waypoints may divert from the original trajectory within a certain tolerance. As a consequence, additional collision checks might be required when using this method. It is the default everywhere in MoveIt2.
Time-optimal Trajectory Generation (TOTG) was introduced in PRs `#809 <https://github.com/ros-planning/moveit/pull/809>`_ and `#1365 <https://github.com/ros-planning/moveit/pull/1365>`_. It produces trajectories with very smooth and continuous velocity profiles. The method is based on fitting path segments to the original trajectory and then sampling new waypoints from the optimized path. This is different from strict time parameterization methods as resulting waypoints may divert from the original trajectory within a certain tolerance. As a consequence, additional collision checks might be required when using this method. It is the default everywhere in MoveIt 2.

Usage of a time parameterization algorithm as a Planning Request Adapter is documented in `this tutorial <../motion_planning_pipeline/motion_planning_pipeline_tutorial.html#using-a-planning-request-adapter>`_.

Expand Down
5 changes: 4 additions & 1 deletion doc/how_to_guides/chomp_planner/launch/chomp_demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="screen",
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ Requirements
Steps
-----

1. Build the MoveIt2 workspace
1. Build the MoveIt 2 workspace

First, ``cd`` to the root directory of the moveit2 workspace. (if you followed the :doc:`Getting Started </doc/tutorials/getting_started/getting_started>` tutorial, this will be ``~/ws_moveit/``).

Expand Down
2 changes: 1 addition & 1 deletion doc/how_to_guides/isaac_panda/.docker/ros_entrypoint.sh
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/bin/bash

# Source ROS and the MoveIt2 workspace
# Source ROS and the MoveIt 2 workspace
source /opt/ros/humble/setup.bash
source /root/ws_moveit/install/setup.bash
echo "Sourced ROS & MoveIt Humble"
Expand Down
9 changes: 5 additions & 4 deletions doc/how_to_guides/isaac_panda/isaac_panda_tutorial.rst
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
How To Command Simulated Isaac Robot
====================================

This tutorial requires a machine with ``Isaac Sim 2022.2.0`` or ``Isaac Sim 2022.2.1`` installed.
This tutorial requires a machine with ``Isaac Sim 2023.1.x`` (recommended) or ``Isaac Sim 2022.2.x`` installed.
For Isaac Sim requirements and installation please see the `Omniverse documentation <https://docs.omniverse.nvidia.com/isaacsim/latest/index.html>`_.
To configure Isaac Sim to work with ROS 2 please see `this guide <https://docs.omniverse.nvidia.com/isaacsim/latest/installation/install_ros.html#running-native-ros>`_.

This tutorial has the following assumptions on system configuration:

1. NVIDIA Isaac Sim 2022.2.0 or 2022.2.1 is installed on a Ubuntu 20.04 host in the default location.
1. NVIDIA Isaac Sim is installed in the default location. Docker based installations of Isaac sim are also supported but it is up to the user to configure the system.
2. Docker is installed.
If you plan to use your GPU with MoveIt, you will need to install `nvidia-docker <https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html#installing-on-ubuntu-and-debian>`_.
3. You clone this repo so that you can build a Ubuntu 22.04 Humble based Docker image that can communicate with Isaac and run this tutorial.
Expand Down Expand Up @@ -70,7 +71,7 @@ Computer Setup

1. Install `Isaac Sim <https://docs.omniverse.nvidia.com/isaacsim/latest/installation/install_workstation.html>`_.

2. Perform a shallow clone of the MoveIt2 Tutorials repo.
2. Perform a shallow clone of the MoveIt 2 Tutorials repo.

.. code-block:: bash
Expand Down Expand Up @@ -118,7 +119,7 @@ Running the MoveIt Interactive Marker Demo with Isaac Sim
2. Then run the following command to load the Panda Robot pre-configured to work with this tutorial.

.. note:: This step assumes Isaac Sim version 2022.2.0 or 2022.2.1 is installed on the host in the ``$HOME/.local/share/ov/pkg/" directory``.
.. note:: This step assumes that a compatible version of Isaac Sim is installed on the host in the ``$HOME/.local/share/ov/pkg/" directory``.
This step also takes a few minutes to download the assets and setup Isaac Sim so please be
patient and don't click the ``Force Quit`` dialog that pops up while the simulator starts.

Expand Down
5 changes: 4 additions & 1 deletion doc/how_to_guides/isaac_panda/launch/isaac_demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="screen",
)

Expand Down
2 changes: 1 addition & 1 deletion doc/how_to_guides/isaac_panda/launch/python.sh
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ ISAAC_SCRIPT_DIRS=()
for ISAAC_SCRIPT_DIR in $(ls -d -- $OV_PKG_DIR/isaac_sim-*);
do
ISAAC_VER=${ISAAC_SCRIPT_DIR//$OV_PKG_DIR\/isaac_sim-/};
if [[ "$ISAAC_VER" =~ ^(2022.2.0|2022.2.1)$ ]]; then
if [[ "$ISAAC_VER" =~ ^(2022.2.0|2022.2.1|2023.1.0|2023.1.1)$ ]]; then
ISAAC_SCRIPT_DIRS+=($ISAAC_SCRIPT_DIR)
fi
done
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ int main(int argc, char** argv)
std::vector<moveit::core::RobotStatePtr> traj;
moveit::core::MaxEEFStep max_eef_step(0.01, 0.1);
// Here, we're effectively disabling the jump threshold for joints. This is not recommended on real hardware.
moveit::core::JumpThreshold jump_thresh(0.0);
const auto jump_thresh = moveit::core::JumpThreshold::disabled();

// The trajectory, traj, passed to computeCartesianPath will contain several waypoints toward
// the goal pose, target. For each of these waypoints, the IK solver is queried with the given cost function.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,10 @@ In our example, we have:
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,10 @@ def launch_setup(context, *args, **kwargs):
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
5 changes: 4 additions & 1 deletion doc/how_to_guides/pick_ik/launch/demo_pick_ik.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,10 @@ def launch_setup(context, *args, **kwargs):
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.robot_description, ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/getting_started/getting_started.rst
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ This build command will likely take a long time (20+ minutes) depending on your
.. warning::
Some of the packages built with this command require up to 16Gb of RAM to build. By default, ``colcon`` tries to build as many packages as possible at the same time.
If you are low on computer memory, or if the build is generally having trouble completing on your computer,
you can try appending ``--executor sequential`` to the ``colcon`` command above to build only one package at a time, or ``-parallel-workers <X>`` to limit the number of simultaneous builds.
you can try appending ``--executor sequential`` to the ``colcon`` command above to build only one package at a time, or ``--parallel-workers <X>`` to limit the number of simultaneous builds.

If everything goes well, you should see the message "Summary: X packages finished" where X might be 50. If you have problems, try re-checking your `ROS Installation <https://docs.ros.org/en/rolling/Installation.html>`_.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,10 @@ def generate_launch_description():
ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[moveit_config.to_dict(), ros2_controllers_path],
parameters=[ros2_controllers_path],
remappings=[
("/controller_manager/robot_description", "/robot_description"),
],
output="both",
)

Expand Down
Loading

0 comments on commit c354f30

Please sign in to comment.