Tutorial for Visual SLAM with Isaac Sim
Overview
This tutorial walks you through a graph to estimate 3D pose of the camera with Visual SLAM using images from Isaac Sim.
Tutorial Walkthrough
Complete the quickstart.
Launch the Docker container using the
run_dev.sh
script:cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh
Install and launch Isaac Sim following the steps in the Isaac ROS Isaac Sim Setup Guide
Press Play to start publishing data from the Isaac Sim.
In a separate terminal, start
isaac_ros_visual_slam
using the launch files:ros2 launch isaac_ros_visual_slam isaac_ros_visual_slam_isaac_sim.launch.py
In a separate terminal, send the signal to move the robot about as follows:
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}}""
In a separate terminal, spin up RViz with default configuration file to see the rich visualizations as the robot moves.
rviz2 -d src/isaac_ros_visual_slam/isaac_ros_visual_slam/rviz/isaac_sim.cfg.rviz
To see the odometry messages, in a separate terminal echo the contents of the
/visual_slam/tracking/odometry
topic with the following command:ros2 topic echo /visual_slam/tracking/odometry
Saving and Using the Map
As soon as you start the visual SLAM node, it starts storing the
landmarks and the pose graph. You can save them in a map and store the
map onto a disk. Make a call to the SaveMap
ROS 2 Action with the
following command:
Note
/path/to/save/the/map
must be a new empty directory every time you call this action because this action overwrites the existing contents.
ros2 action send_goal /visual_slam/save_map isaac_ros_visual_slam_interfaces/action/SaveMap "{map_url: /path/to/save/the/map}"
Try to load and localize in the previously saved map.
Stop the visual_slam
node launched for creating and saving the
map, then relaunch it.
Use the following command to load the map from the disk and provide an approximate start location (prior):
ros2 action send_goal /visual_slam/load_map_and_localize isaac_ros_visual_slam_interfaces/action/LoadMapAndLocalize "{map_url: /path/to/save/the/map, localize_near_point: {x: x_val, y: y_val, z: z_val}}"
After the above step returns success, you have successfully loaded and localized your robot in the map. If it results in failure, there might be a possibility that the current landmarks from the approximate start location are not matching with stored landmarks and you need to provide another valid value.