6.6.1 Isaac Sim Simulation Mapping
Last Version: 19/09/2025
This guide explains how to set up and use Isaac Sim on a GPU server with Isaac ROS in a Docker container to perform mapping and navigation simulation.
⚠️ Environment Note:
- Isaac Sim runs on a GPU server, while Isaac ROS operates in a Docker container (e.g., isaac-ros-dev) deployed on the same GPU server.
- Official Tutorial: Isaac ROS Official Example
Overview
The Isaac ROS VSLAM (Visual Simultaneous Localization and Mapping) solution fuses data from multiple sensors (Stereo Camera, IMU, Wheel Encoder, LiDAR) to provide positioning and odometry information for navigation. This data drives the ROS 2 Navigation Stack (Nav2). The system’s main goal is to generate accurate /odom
and /amcl_pose
messages.
- Stereo Camera + IMU: Combines stereo vision and inertial measurement for visual odometry and relocalization (positioning).
- Wheel Encoder: Uses wheel encoder data (incremental position) to assist with positioning.
- LiDAR: Employs Adaptive Monte Carlo Localization (particle filter method) with LaserScan and map data for global positioning.
Preparation
Step 1: Download Offline Resources
Log in to the AI server and download the resource package for the Isaac ROS VSLAM example:
NGC_ORG="nvidia"
NGC_TEAM="isaac"
PACKAGE_NAME="isaac_ros_visual_slam"
NGC_RESOURCE="isaac_ros_visual_slam_assets"
NGC_FILENAME="quickstart.tar.gz"
MAJOR_VERSION=3
MINOR_VERSION=2
VERSION_REQ_URL="https://catalog.ngc.nvidia.com/api/resources/versions?orgName=$NGC_ORG&teamName=$NGC_TEAM&name=$NGC_RESOURCE&isPublic=true&pageNumber=0&pageSize=100&sortOrder=CREATED_DATE_DESC"
AVAILABLE_VERSIONS=$(curl -s \
-H "Accept: application/json" "$VERSION_REQ_URL")
LATEST_VERSION_ID=$(echo $AVAILABLE_VERSIONS | jq -r "
.recipeVersions[]
| .versionId as \$v
| \$v | select(test(\"^\\\\d+\\\\.\\\\d+\\\\.\\\\d+$\"))
| split(\".\") | {major: .[0]|tonumber, minor: .[1]|tonumber, patch: .[2]|tonumber}
| select(.major == $MAJOR_VERSION and .minor <= $MINOR_VERSION)
| \$v
" | sort -V | tail -n 1
)
if [ -z "$LATEST_VERSION_ID" ]; then
echo "No corresponding version found for Isaac ROS $MAJOR_VERSION.$MINOR_VERSION"
echo "Found versions:"
echo $AVAILABLE_VERSIONS | jq -r '.recipeVersions[].versionId'
else
mkdir -p ${ISAAC_ROS_WS}/isaac_ros_assets && \
FILE_REQ_URL="https://api.ngc.nvidia.com/v2/resources/$NGC_ORG/$NGC_TEAM/$NGC_RESOURCE/\
versions/$LATEST_VERSION_ID/files/$NGC_FILENAME" && \
curl -LO --request GET "${FILE_REQ_URL}" && \
tar -xf ${NGC_FILENAME} -C ${ISAAC_ROS_WS}/isaac_ros_assets && \
rm ${NGC_FILENAME}
fi
These resources include offline bag files and interface configuration files for the Isaac ROS VSLAM example, which can be used to test the VSLAM algorithm offline.
Step 2: Install/Compile Isaac ROS Visual SLAM
Enter the isaac-ros-dev
environment and install or compile the isaac-ros-visual-slam
package.
-
Option 1: Install Precompiled Package:
sudo apt-get update
sudo apt-get install -y ros-humble-isaac-ros-visual-slam -
Option 2: Compile from Source:
cd ${ISAAC_ROS_WS}/src
git clone -b release-3.2 https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_visual_slam.git isaac_ros_visual_slam
sudo apt-get update
rosdep update && rosdep install --from-paths ${ISAAC_ROS_WS}/src/isaac_ros_visual_slam/isaac_ros_visual_slam --ignore-src -y
cd ${ISAAC_ROS_WS}/
colcon build --symlink-install --packages-up-to isaac_ros_visual_slam --base-paths ${ISAAC_ROS_WS}/src/isaac_ros_visual_slam/isaac_ros_visual_slam
source install/setup.bash
Launching the Simulation
Run the simulation on the GPU server.
Step 1: Start Isaac Sim
cd isaacsim
./isaac-sim.sh
Step 2: Load the Scene and AGV Model
Refer to: https://nvidia-isaac-ros.github.io/getting_started/isaac_sim/index.html
Step 3: Start the Simulation
Click the PLAY button on the left side of the view. This step:
- Activates the simulation scene
- Powers on the AGV and sensors
- Enables sensor data collection and topic publishing
- Prepares controllers to listen to subscribed topics (e.g., velocity commands)
Launching Isaac ROS VSLAM
Start the Isaac ROS VSLAM within the isaac-ros-dev
environment.
Step 1: Start the VSLAM System
ros2 launch isaac_ros_visual_slam isaac_ros_visual_slam_isaac_sim.launch.py
This command
- launches the VSLAM algorithm node, which automatically subscribes to camera sensor data and TF transform information from Isaac Sim.
- performs visual odometry and map building.
- and publishes positioning and perception data (e.g., odometry, point cloud maps) for other modules.
Step 2: Publish /cmd_vel
Topic
Open a ROS 2 terminal (can be on isaac-ros-dev
, a PC, or K1 board, as long as it's in the same ROS 2 domain) and send a velocity command to the AGV:
ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.2, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.2}}"
The above command publishes to the /cmd_vel
topic, which is subscribed by Isaac Sim's differential drive controller to move the AGV. It sets a linear speed of 0.2 m/s and an angular speed of 0.2 rad/s, to make the AGV move counterclockwise in a 1m-radius circle.
This will make the robot move in a counter-clockwise circular path with 1m radius at constant speed.
Alternatively, use the teleop_twist_keyboard
node to control the AGV:
ros2 run teleop_twist_keyboard teleop_twist_keyboard
Step 3: RViz Visualization
Open a new isaac-ros-dev
window and load the visualization configuration in RViz2:
rviz2 -d $(ros2 pkg prefix isaac_ros_visual_slam --share)/rviz/isaac_sim.cfg.rviz
Step 4: View Odometry Information
Open a ROS 2 window (e.g., isaac-ros-dev
, PC, or K1, within the same ROS 2 domain) to check the AGV’s odometry data:
ros2 topic echo /visual_slam/tracking/odometry
Saving the Map
Step 1: Check if the Map is Ready
Criteria for VSLAM to determine if a map is ready:
- Stable Localization
- No loss of tracking or drift.
- Check the
/visual_slam/status
topic for the absence ofTRACK_LOST
orTRACKING_WEAK
states.
- Map Convergence
- Stable point cloud or keyframes.
- Monitor the
/visual_slam/vis/landmarks_cloud
topic. The rate of new feature points should drop significantly as mapping nears completion.
Step 2: Save the Map Locally
Isaac ROS provides a custom service to save the map:
ros2 service call /visual_slam/save_map isaac_ros_visual_slam_interfaces/srv/FilePath "{file_path: /path/to/save/the/map}"
Note: The /path/to/save/the/map
must be an empty directory, as it will overwrite any existing content.
The saved map is in .mdb
format which is a unique Isaac ROS map data format:
admin@ai-site-4090d:/workspaces/isaac_ros-dev$ ros2 service call /visual_slam/save_map isaac_ros_visual_slam_interfaces/srv/FilePath "{file_path: /tmp/map}"
requester: making request: isaac_ros_visual_slam_interfaces.srv.FilePath_Request(file_path='/tmp/map')
response:
isaac_ros_visual_slam_interfaces.srv.FilePath_Response(success=True)
admin@ai-site-4090d:/workspaces/isaac_ros-dev$ ls -al /tmp/map
total 26436
drwxr-xr-x 2 admin admin 4096 May 29 11:22 .
drwxrwxrwt 1 root root 4096 May 29 11:22 ..
-rw-r--r-- 1 admin admin 27062272 May 29 11:22 data.mdb
Using the Saved Map
-
Restart the VSLAM Node
ros2 launch isaac_ros_visual_slam isaac_ros_visual_slam_isaac_sim.launch.py
-
Load the Map and Localize Provide an initial position to load the map and localize:
ros2 service call /visual_slam/localize_in_map isaac_ros_visual_slam_interfaces/srv/LocalizeInMap "
map_folder_path: '/path/to/save/the/map'
pose_hint:
position:
x: x-position
y: y-position
z: z-position
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0"
If it fails, the position might be too similar to another location in the map, causing VSLAM to misjudge. Try a different initial position.