Set Up and Connect to NVIDIA Isaac Sim
This example shows how to set up and interact with the NVIDIA Isaac Sim® [1] application from MATLAB® through a ROS 2 interface.
NVIDIA Isaac Sim, powered by Omniverse® [2], is a scalable robotics simulation application and synthetic data generation tool that powers photorealistic, physically accurate virtual environments. You can use NVIDIA Isaac Sim to develop, test, and manage AI-based robots. NVIDIA Omniverse is a computing platform that enables individuals and teams to develop universal-scene-description-based (USD-based) [3] 3-D workflows and applications.
Configure Workstation
Ensure your local workstation meets the System Requirements and Isaac Sim Driver Requirements [4] for running Omniverse Isaac Sim.
Visit Omniverse Downloads to download the standard version of Omniverse Launcher, which is the native client for downloading, installing, and updating Omniverse applications, extensions, and connectors.
Install Omniverse Launcher [5].
Install Isaac Sim and Omniverse Cache [6] from the Exchange tab in the Omniverse Launcher.
Install Nucleus [7] from the Omniverse Launcher to access Isaac environments, assets, and samples.
Install and Activate ROS 2 Environment
Refer to ROS Toolbox System Requirements to find the MATLAB® release-specific supported ROS 2 distribution for Windows platform. Follow the ROS 2 Windows binary installation instructions from ROS 2 Documentation to install the supported ROS 2 distribution on your Windows workstation. For example, follow the instructions on the ROS 2 Humble Installation page [8] to install ROS 2 Humble distribution.
From the start menu, look for developer command prompt: run the
x64
Native
Tools
Command
Prompt
for
VS
2019
shortcut as an administrator.Activate the ROS 2 environment by sourcing the ROS 2 installation. For example, run this command in the command prompt to install ROS 2 Humble:
call C:\opt\ros\humble\x64\setup.bat
in the command prompt.
Launch Isaac Sim
Launch NVIDIA Isaac Sim from the same command prompt in which you activate the ROS 2 installation environment. Navigate to your Isaac Sim installation location using cd <path_to_isaac_sim_install_path>
. If you do not know where the Isaac Sim application is installed, follow these steps to locate the installation path.
1. Go to the Library tab in the Omniverse Launcher. Select Isaac Sim in the Apps pane on the left.
2. Open the Isaac Sim Settings panel by clicking Settings.
3. Click the folder icon in the settings panel to open the Isaac Sim installation location in the explorer.
4. Copy the Isaac Sim location and navigate to that folder in the same command prompt in which you activate the ROS 2 environment.
5. Set the FASTRTPS_DEFAULT_PROFILES_FILE
environment variable to <path_to_isaac_sim_install_path>\ros2_workspace\fastdds.xml
before launching Isaac Sim. For example, run this command in the command prompt:set FASTRTPS_DEFAULT_PROFILES_FILE=C:\Users\Paul\AppData\Local\ov\pkg\isaac_sim-2022.2.1\ros2_workspace\fastdds.xml.
6. Run isaac-sim.bat
to launch Isaac Sim. The first run of the Isaac Sim application takes up to five minutes to warm up the shader cache.
Enable ROS 2 Bridge Extension
To enable the ROS 2 bridge (omni.isaac.ros2_bridge) extension, go to the Extensions menu under the Window tab. Then, search for ROS2 Bridge and enable it. This extension connects Isaac Sim to ROS 2.
Set Up Scene in Isaac Sim
To load the warehouse scene in Isaac Sim, follow these steps:
1. Navigate to this location under Content tab in Isaac Sim : omniverse://localhost/NVIDIA/Assets/Isaac/2022.2.1/Isaac/Samples/ROS2/Scenario.
2. Drag the carter_warehouse_navigation
file with.usd
extension to the Viewport in Isaac Sim. This action loads a warehouse scenario containing a Carter robot that uses its RTX lidar and a camera to perceive the world. Loading the scene for the first time takes several minutes.
3. To begin the simulation, click Play.
Verify Topics Published by Carter Robot in MATLAB
Query available topics in the ROS 2 network. Ensure that the warehouse scene is playing in NVIDIA Isaac Sim to see the topics that the Carter robot publishes.
ros2 topic list
References
[1] NVIDIA Developer. “Isaac Sim,” December 11, 2019. https://developer.nvidia.com/isaac-sim.
[2] “NVIDIA Omniverse Documentation.” Accessed July 27, 2023. https://docs.omniverse.nvidia.com/.
[3] NVIDIA. “Universal Scene Description (USD) at NVIDIA.” Accessed July 27, 2023. https://www.nvidia.com/en-us/omniverse/usd/.
[4] “1. Isaac Sim Requirements — Isaacsim Latest Documentation.” Accessed July 27, 2023. https://docs.omniverse.nvidia.com/isaacsim/latest/requirements.html.
[5] “Installing Launcher — Launcher Latest Documentation.” Accessed July 27, 2023. https://docs.omniverse.nvidia.com/launcher/latest/installing_launcher.html.
[6] “Workstation — Utilities Latest Documentation.” Accessed July 27, 2023. https://docs.omniverse.nvidia.com/utilities/latest/cache/installation/workstation.html.
[7] “Installation — Nucleus Latest Documentation.” Accessed July 27, 2023. https://docs.omniverse.nvidia.com/nucleus/latest/workstation/installation.html.
[8] “Windows (Binary) — ROS 2 Documentation: Humble Documentation.” Accessed April 29, 2024. https://docs.ros.org/en/humble/Installation/Windows-Install-Binary.html.