1. ROS2 Navigation¶
1.1. Learning Objectives¶
In this ROS2 sample, we are demonstrating Omniverse Isaac Sim integrated with the ROS2 Nav2 project.
1.2. Getting Started¶
Prerequisite
This ROS2 Navigation sample is only supported on ROS2 Foxy Fitzroy or later. See the ROS2 website for requirements and installation instructions: https://docs.ros.org/en/foxy/Releases/Release-Foxy-Fitzroy.html
The Nav2 project is required to run this sample. To install the Nav2 project refer to the Nav2 installation page.
The ROS2
teleop_twist_keyboard
package is also required. To install the package run the following:
sudo apt-get install ros-$ROS_DISTRO-teleop-twist-keyboard
Enabled the omni.isaac.ros2_bridge extension from the extension manager menu Windows->Extensions.
We use the
carter_navigation
ROS2 package which contains the required launch file and navigation parameters. Thecarter_description
ROS2 package is also used for displaying the NVIDIA Carter robot model in RViz2. Both ROS2 packages are located under the directoryros2_workspace/src/navigation/
. Complete ROS & ROS2 Installation, make sure ROS environment is setup correctly and those packages are inside your ROS_PACKAGE_PATH.
1.3. 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
/scan
sensor_msgs/LaserScan
1.3.1. Omniverse Isaac Sim TF broadcasting in more detail:¶
ROS_DifferentialBase
subscribes to the /cmd_vel topic and is responsible for controlling the movement of the robot.
It also publishes the transform between the odom frame and base_link frame.
ROS_Carter_Broadcaster
is responsible for publishing the static
transform between the base_link frame and chassis_link frame. Keep in mind that since the target prim is set as Carter_ROS
, the entire transform tree of the Carter robot (with chassis_link as root) will be published alongside the base_link frame.
ROS_Carter_Lidar_Broadcaster
is responsible for publishing the static transform between the chassis_link frame and carter_lidar frame.
Finally, to ensure all ROS2 nodes reference simulation time, a ROS_Clock
prim has been added which publishes the simulation time to the /clock ROS2 topic.
1.3.2. 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 -> ROS -> Navigation to load the warehouse scenario.
Press
Play
to begin simulation.At the upper left corner of the viewport, click on carter_camera_stereo_left. 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: 10.0
. For the Upper Bound, setZ: 62.0
. Keep in mind, the upper bound Z distance has been set to 62.0 cm 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 image:
A perimeter will be generated and it should resemble this image (Top View):
Ensure the Carter_ROS prim is removed from the stage.
Once the setup is complete, click on
CALCULATE
followed byVISUALIZE IMAGE
. A Visualization popup will appear.For rotation, select 180 degrees and for Coordinate Type select
ROS Occupancy Map Parameters File (YAML)
. ClickRE-GENERATE IMAGE
.Occupancy map parameters formatted to YAML will appear in the field below. Copy the full text.
11. Create a YAML file for the occupancy map parameters called carter_warehouse_navigation.yaml
and place it in the maps directory which is located in the sample carter_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 ascarter_warehouse_navigation.png
and choose to save in the same directory as the map parameters file.
The final saved image will look like the following:
If not done so already, click
Stop
to terminate the simulation.
An occupancy map is now ready to be used with Nav2!
1.4. Running Nav2¶
Go to Isaac Examples -> ROS -> 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 will open and begin loading the occupancy map. If a map does not appear, repeat the previous step.
4. Load the the URDF model into the RViz2 window by clicking on RobotModel -> Description File and navigate to the location
of the Carter URDF model which can be found at the urdf directory in the sample carter_description ROS2 package (carter_description/urdf/carter.urdf
).
It is mostly likely after launching
carter_navigation.launch.py
, that the local costmap will not match the occupancy map. This means the robot is not correctly localized. To mitigate this, click on the2D Pose Estimate
button near the top of the RViz2 window and set the initial estimated pose by clicking and dragging at a point on the map where you think the robot is located.
6. To get a better idea of where the robot is located, you may wish to change camera views by clicking at the top left of the viewport in the Omniverse Isaac Sim window.
In RViz2, the robot model will immediately jump to the indicated pose. The local costmap should now be similarly aligned to the occupancy map.
Note
The local and occupancy maps don’t have to perfectly align yet. However if their alignment is quite different, you may repeat the previous step until getting a closer alignment.
7. To make both the local and global maps properly align, manually drive around the robot (rotating in place works the fastest in most cases). For manually controlling the robot, run the teleop_twist_keyboard ROS2 node using the following command in a new terminal.
ros2 run teleop_twist_keyboard teleop_twist_keyboard
Use the keyboard to move the robot until the local costmap has properly aligned with the occupancy map.
Now the robot has been properly localized! You may now stop the teleop_twist_keyboard node as it is not required anymore.
9. Click on the Navigation2 Goal
button and then click and drag at the desired location point in the map.
Nav2 will now generate a trajectory and the robot will start moving towards its destination!
1.5. Summary¶
In this tutorial, we covered running Isaac Sim with ROS2 navigation stack.
1.5.1. Next Steps¶
Go to the next tutorial Multiple Robot ROS2 Navigation to move multiple navigating robots with ROS2.
1.5.2. Further Learning¶
To learn more about Nav2, refer to the project website: https://navigation.ros.org/index.html