ROS2 Navigation
Note
ROS 2 Navigation with Isaac Sim is fully supported on Linux. On Windows, ROS 2 Navigation with Isaac Sim is partially supported and could potentially produce errors.
Warning
ROS 2 Foxy is no longer tested or supported. This may result in potential issues when ROS 2 Foxy is used in conjunction with Isaac Sim 4.2 or later. ROS 2 Foxy Isaac Sim tutorial packages will be removed in a future release.
Learning Objectives
This ROS2 sample demonstrates Omniverse Isaac Sim integrated with ROS2 Nav2.
Getting Started
Important
Make sure to source your ROS 2 installation from the terminal before running Isaac Sim. If sourcing ROS 2 is a part of your bashrc
then Isaac Sim can be run directly.
Prerequisite
This ROS2 Navigation sample is only supported on ROS2 Foxy and Humble.
The Nav2 project is required to run this sample. To install Nav2 refer to the Nav2 installation page.
Enable the
omni.isaac.ros2_bridge
Extension in the Extension Manager window by navigating to Window > Extensions.This tutorial requires
carter_navigation
,iw_hub_navigation
andisaac_ros_navigation_goal
ROS2 packages, which are provided as part of your Omniverse Isaac Sim download. These ROS2 packages are located inside the appropriateros2_ws
(foxy_ws
orhumble_ws
). They contain the required launch file, navigation parameters, and robot model. Complete ROS and ROS 2 Installation, make sure the ROS2 workspace environment is setup correctly.
Note
In Windows 10 or 11, depending on your machine’s configuration, RViz2 may not open properly.
Nav2 Setup
This block diagram shows the ROS2 messages required for Nav2:
As described above, the following topics and message types being published to Nav2 in this scenario are:
ROS2 Topic
ROS2 Message Type
/tf
tf2_msgs/TFMessage
/odom
nav_msgs/Odometry
/map
nav_msgs/OccupancyGrid
/point_cloud
sensor_msgs/PointCloud
/scan
sensor_msgs/LaserScan (published by an external pointcloud_to_laserscan node)
Occupancy Map
In this scenario, an occupancy map is required. For this sample, we are generating an occupancy map of the warehouse environment using the Occupancy Map Generator extension within Omniverse Isaac Sim.
Go to Isaac Examples -> ROS2 -> Navigation -> Carter Navigation to load the warehouse scenario with the Nova Carter robot.
At the upper left corner of the viewport, click on Camera. Select Top from the dropdown menu.
Go to Isaac Utils -> Occupancy Map.
In the Occupancy Map extension, ensure the Origin is set to
X: 0.0, Y: 0.0, Z: 0.0
. For the lower bound, setZ: 0.1
. For the Upper Bound, setZ: 0.62
. Keep in mind, the upper bound Z distance has been set to 0.62 meters to match the vertical distance of the Lidar onboard Carter with respect to the ground.Select the
warehouse_with_forklifts
prim in the stage. In the Occupancy Map extension, click on BOUND SELECTION. The bounds of the occupancy map should be updated to incorporate the selected warehouse_with_forklifts prim. The map parameters should now look similar to the following:Verify that a perimeter is generated and that it resembles this Top View:
Remove the
Nova_Carter_ROS
prim from the stage.Once the setup is complete, click on CALCULATE followed by VISUALIZE IMAGE. A Visualization popup will appear.
For Rotate Image, select 180 degrees and for Coordinate Type select ROS Occupancy Map Parameters File (YAML). Click RE-GENERATE IMAGE. The ROS camera and Isaac Sim camera have different coordinates.
Occupancy map parameters formatted to YAML appears in the field below. Copy the full text.
Create a YAML file for the occupancy map parameters called
carter_warehouse_navigation.yaml
and place it in themaps
directory, which is located in the samplecarter_navigation
ROS2 package (carter_navigation/maps/carter_warehouse_navigation.yaml
).Insert the previously copied text in the
carter_warehouse_navigation.yaml
file.Back in the visualization tab in Omniverse Isaac Sim, click Save Image. Name the image as
carter_warehouse_navigation.png
and choose to save it in the same directory as the map parameters file.Verify that the final saved image looks like the following:
An occupancy map is now ready to be used with Nav2!
Running Nav2
Nav2 with Nova Carter in Small Warehouse
Go to Isaac Examples -> ROS2 -> Navigation -> Carter Navigation to load the warehouse scenario with the Nova Carter robot.
Click on Play to begin simulation.
In a new terminal, run the ROS2 launch file to begin Nav2.
ros2 launch carter_navigation carter_navigation.launch.py
RViz2 opens and begins loading the occupancy map. If a map does not appear, repeat the previous step.
Since the position of the robot is defined in the parameter file
carter_navigation_params.yaml
, the robot should already be properly localized. If required, the 2D Pose Estimate button can be used to re-set the position of the robot.Click on the Navigation2 Goal button and then click and drag at the desired location point in the map. Nav2 now generates a trajectory and the robot starts moving towards its destination!
(Optional) You can add the Isaac ROS Nova Carter robot description by setting up and building the package. Follow the Using the Nova Carter Description Package (Optional) section to learn more.
Note
The Carter robot uses the RTX Lidar by default. You can add people assets into the scene and they will be detected by the Lidar when being passed to Nav2.
Note
Some of the ROS2 Image publisher pipelines in the hawk cameras are disabled by default to improve performance. To start publishing images, open the _hawk
action graphs found under the robot prim and enable the _camera_render_product
nodes. The ROS Camera publisher nodes, which are downstream of the render product nodes, should be enabled by default and only start publishing when the render product node is enabled. All sensors and images in Nova Carter are being published with Sensor Data QoS. If you wish to visualize the images in RViz please expand the image tab, navigate to Topic > Reliability Policy and change the policy to Best Effort.
Note
If running Nav2 with ROS2 Foxy, you may notice issues with localizing the robot in open spaces. This is a known issue likely attributed to lower performance. To improve localization, you could add more objects into the scene to introduce more features.
Note
If you notice warnings as shown below, you can disregard them because they are harmless.
[Warning] [omni.graph.core.plugin] /World/Nova_Carter_ROS/differential_drive/differential_controller_01: [/World/Nova_Carter_ROS/differential_drive] invalid dt 0.000000, cannot check for acceleration limits, skipping current step
Using the Nova Carter Description Package (Optional)
Note
This section is only supported in Linux ROS2 Humble. The Nova Carter description package is not supported in WSL2.
The Nova Carter description package contains the robot geometry including meshes that can be used to visualize the robot in RViz2. Follow the steps below to configure this description package for Isaac Sim workflows:
Complete the steps outlined in the Isaac ROS Development Environment Setup.
Complete the steps outlined in the Repositories Setup.
In a new terminal navigate to the folder containing launch files in the nova_carter_description package and create a new file called
nova_carter_description_isaac_sim.launch.py
.cd ${ISAAC_ROS_WS}/src/nova_carter/nova_carter_description/launch gedit nova_carter_description_isaac_sim.launch.py
Copy the following snippet into the new file and save.
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES # Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 # # Unless required by applicable law or agreed to in writing, software # distributed under the License is distributed on an "AS IS" BASIS, # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. # # SPDX-License-Identifier: Apache-2.0 # flake8: noqa: F403,F405 import isaac_ros_launch_utils as lu from isaac_ros_launch_utils.all_types import * from launch import LaunchDescription from launch_ros.actions import Node def generate_launch_description() -> LaunchDescription: args = lu.ArgumentContainer() args.add_arg('calibrated_urdf_file', default='/etc/nova/calibration/isaac_calibration.urdf') return LaunchDescription([ lu.add_robot_description(nominals_package='nova_carter_description', nominals_file='urdf/nova_carter.urdf.xacro', robot_calibration_path=args.calibrated_urdf_file), ])
Inside the Docker container build all the dependencies for nova_carter_description package.
cd /workspaces/isaac_ros-dev colcon build --packages-up-to nova_carter_description
In the Docker container source the isaac_ros-dev workspace and run the custom launch file that you just created above to start publishing the robot description to the
/robot_descritption
topic.source /workspaces/isaac_ros-dev/install/setup.bash ros2 launch nova_carter_description nova_carter_description_isaac_sim.launch.py
Outside of the container (on the host), open a new terminal and ensure ROS is installed and that the Isaac Sim Workspace is sourced. Additionally, source the
nova_carter_description
package workspace in a new terminal.source ${ISAAC_ROS_WS}/install/setup.bash
In the same terminal run the ~carter_navigation~ launch file:
ros2 launch carter_navigation carter_navigation.launch.py
Verify that the robot model is automatically loaded in the scene in Rviz.
Nav2 with iw.hub in Warehouse
Go to Isaac Examples -> ROS2 -> Navigation -> iw.hub Navigation to load the warehouse scenario with the iw.hub robot.
Click on Play to begin simulation.
In a new terminal, run the ROS2 launch file to begin Nav2. The map for the different warehouse environment has already been generated.
ros2 launch iw_hub_navigation iw_hub_navigation.launch.py
RViz2 opens and begins loading the occupancy map. If a map does not appear, repeat the previous step.
Since the position of the robot is defined in the parameter file
iw_hub_navigation_params.yaml
, the robot should already be properly localized. If required, the 2D Pose Estimate button can be used to re-set the position of the robot.Click on the Navigation2 Goal button and then click and drag at the desired location point in the map. Nav2 now generates a trajectory and the robot starts moving towards its destination! The robot should avoid dynamic obstacles such the pallets that are in scene but are not included in the initial map.
Sending Goals Programmatically
Note
The isaac_ros_navigation_goal
package is fully supported on Linux. On Windows, running this package could potentially produce errors.
The isaac_ros_navigation_goal
ROS2 package can be used to set goal poses for the robot using a python node. It is able to randomly generate and send goal poses to Nav2. It is also able to send user-defined goal poses if needed.
Make any changes to the parameters defined in the launch file found under
isaac_ros_navigation_goal/launch
as required. Make sure to re-build and source the package/workspace after modifying its contents.The parameters are described below:
goal_generator_type: Type of the goal generator. Use
RandomGoalGenerator
to randomly generate goals or useGoalReader
for sending user-defined goals in a specific order.map_yaml_path: The path to the occupancy map parameters yaml file. Example file is present at
isaac_ros_navigation_goal/assets/carter_warehouse_navigation.yaml
. The map image is being used to identify the obstacles in the vicinity of a generated pose. Required if goal generator type is set asRandomGoalGenerator
.iteration_count: Number of times goal is to be set.
action_server_name: Name of the action server.
obstacle_search_distance_in_meters: Distance in meters in which there should not be any obstacle of a generated pose.
goal_text_file_path: The path to the text file which contains user-defined static goals. Each line in the file has a single goal pose in the following format:
pose.x pose.y orientation.x orientation.y orientation.z orientation.w
. Sample file is present at:isaac_ros_navigation_goal/assets/goals.txt
. Required if goal generator type is set asGoalReader
.initial_pose: If initial_pose is set, it will be published to /initialpose topic and goal poses will be sent to action server after that. Format is
[pose.x, pose.y, pose.z, orientation.x, orientation.y, orientation.z, orientation.w]
.
Go to Isaac Examples -> ROS2 -> Navigation -> Carter Navigation to load the warehouse scenario.
Click on Play to begin simulation.
In a new terminal, run the ROS2 launch file to begin Nav2.
ros2 launch carter_navigation carter_navigation.launch.py
RViz2 opens and begins loading the occupancy map. If a map does not appear, repeat the previous step.
Run the isaac_ros_navigation_goal launch file, to start sending goals automatically:
ros2 launch isaac_ros_navigation_goal isaac_ros_navigation_goal.launch.py
Note
The package stops processing (setting goals) once any of the below conditions are met:
Number of goals published till now >= iteration_count.
If
GoalReader
is being used then if all the goals from file are published, or if condition (1) is true.A goal is rejected by the action server.
In case of
RandomGoalGenerator
, if a goal was not generated even after running the maximum number of iterations, which is rare but could happen in very dense maps.
To learn more about programmatically sending navigation goals to multiple robots simultaneously see Sending Goals Programmatically for Multiple Robots.
Summary
In this tutorial, we covered:
Occupancy map.
Running Isaac Sim with Nav2.
Running the Isaac ROS2 Navigation Goal package to send nav goals programmatically.
Next Steps
Continue on to the next tutorial in our ROS2 Tutorials series, Multiple Robot ROS2 Navigation to move multiple navigating robots with ROS2.
Further Learning
To learn more about Nav2, refer to the project website.
More about Mapping.
Explore the inner workings of RTX Lidar sensors by learning How They work, the RTX Lidar Nodes that use them, and how to get RTX Lidar Synthetic Data.