This tutorial walks you through a graph to estimate 3D pose of the camera with Visual SLAM using images from Isaac Sim.
Last validated with Isaac Sim 2022.2.1
-
Complete the Quickstart section in the main README.
-
Launch the Docker container using the
run_dev.shscript:cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \ ./scripts/run_dev.sh
-
Inside the container, build and source the workspace:
cd /workspaces/isaac_ros-dev && \ colcon build --symlink-install && \ source install/setup.bash
-
Install and launch Isaac Sim following the steps in the Isaac ROS Isaac Sim Setup Guide
-
Open up the Isaac ROS Common USD scene (using the Content tab) located at:
http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/2022.2.1/Isaac/Samples/ROS2/Scenario/carter_warehouse_apriltags_worker.usdAnd wait for it to load completely.
-
Go to the Stage tab and select
/World/Carter_ROS/ROS_Cameras/ros2_create_camera_right_info, then in Property tab -> OmniGraph Node -> Inputs -> stereoOffset X change0to-175.92. -
Enable the right camera for a stereo image pair. Go to the Stage tab and select
/World/Carter_ROS/ROS_Cameras/enable_camera_right, then tick the Condition checkbox. -
Press Play to start publishing data from the Isaac Sim application.
-
In a separate terminal, start
isaac_ros_visual_slamusing 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 rotate the robot about its own axis as follows:
ros2 topic pub /cmd_vel geometry_msgs/Twist '{linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0,y: 0.0,z: 0.05}}' -
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/default.cfg.rviz
-
To see the odometry messages, in a separate terminal echo the contents of the
/visual_slam/tracking/odometrytopic with the following command:ros2 topic echo /visual_slam/tracking/odometry
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/mapmust be a new empty directory everytime you call this action as this action will overwrite 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}"Now, you will try to load and localize in the previously saved map. First, stop the visual_slam node lauched 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}}"Once 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 possibilty that the current landmarks from the approximate start location are not matching with stored landmarks and you need to provide another valid value.









