Detecting Objects in Isaac Sim and ROS2
By Andrés Escobar and Santiago Ferreiros
This blog explores how to perform object detection in a virtual environment using NVIDIA Isaac Sim and ROS2. The setup involves controlling a forklift within a virtual warehouse using keyboard inputs. A front-facing camera mounted on the forklift captures images of the environment. These images are transmitted via Action Graph to a ROS2 node. A custom ROS2 package processes the images and uses the YOLOv8 model to perform object detection. The detection results are then visualized in real-time using RViz2, enabling seamless integration and monitoring of the object detection process within the simulated environment.
Setting Up the EC2 Instance
To begin, launch an EC2 instance and configure it according to the detailed instructions provided in the blog “Deploying NVIDIA Omniverse with Isaac Sim on AWS: A Step-by-Step Guide”. Follow the steps under the sections AWS Instance Launching and Instance Main Setup. These steps ensure that your EC2 instance is properly configured for running Isaac Sim.
- Use an NVIDIA GPU-enabled instance (e.g., g5.2xlarge) to support Isaac Sim.
- Install necessary drivers and software for running Isaac Sim.
Creating a Docker image with ROS2 and Isaac Sim
Once the EC2 instance is ready, create a folder named Isaac-ros2-object-detection to organize the project files. Inside this folder, create a Dockerfile with the following content:
FROM nvcr.io/nvidia/isaac-sim:4.2.0 # 1) Basic environment settings ENV DEBIAN_FRONTEND=noninteractive ENV TZ=America/New_York # 2) Install system dependencies RUN apt-get update && apt-get install -y \ curl gnupg2 lsb-release tzdata software-properties-common # 3) Add ROS 2 keys and repository RUN curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | apt-key add - \ && echo "deb http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" \ > /etc/apt/sources.list.d/ros2-latest.list # 4) Install ROS 2 Humble + teleop + editor RUN apt-get update && apt-get install -y \ ros-humble-desktop \ ros-humble-teleop-twist-keyboard \ nano # 4.1) Install colcon RUN apt-get update && apt-get install -y python3-colcon-common-extensions # 5) Install pip3 and update pip RUN apt-get update && apt-get install -y python3-pip RUN python3 -m pip install --upgrade pip # 6) Install PyTorch (CUDA 11.7) before Ultralytics RUN python3 -m pip install torch torchvision torchaudio \ --index-url https://download.pytorch.org/whl/cu117 # 7) Force NumPy <2 and then install Ultralytics RUN python3 -m pip install --upgrade --force-reinstall "numpy<2" RUN python3 -m pip install ultralytics # 8) Configure ROS environment in root's .bashrc SHELL ["/bin/bash", "-c"] RUN echo "source /opt/ros/humble/setup.bash" >> /root/.bashrc # 9) ROS 2 environment variables ENV ROS_VERSION=2 ENV ROS_PYTHON_VERSION=3 ENV ROS_DISTRO=humble # 10) Reset DEBIAN_FRONTEND ENV DEBIAN_FRONTEND=dialog # 11) Default entry point ENTRYPOINT ["/bin/bash"]
Building the Docker Image:
- Navigate to the folder where the Dockerfile is located.
- Build the Docker image by running
docker build -t isaac-sim-ros2:4.2.0 .
Running the Isaac Sim Container
Start the Docker container using the following command:
docker run --name isaac-sim --entrypoint bash -it --gpus all \ -e "ACCEPT_EULA=Y" --rm --network=host \ -e "PRIVACY_CONSENT=Y" \ -v ~/docker/isaac-sim/cache/kit:/isaac-sim/kit/cache:rw \ -v ~/docker/isaac-sim/cache/ov:/root/.cache/ov:rw \ -v ~/docker/isaac-sim/cache/pip:/root/.cache/pip:rw \ -v ~/docker/isaac-sim/cache/glcache:/root/.cache/nvidia/GLCache:rw \ -v ~/docker/isaac-sim/cache/computecache:/root/.nv/ComputeCache:rw \ -v ~/docker/isaac-sim/logs:/root/.nvidia-omniverse/logs:rw \ -v ~/docker/isaac-sim/data:/root/.local/share/ov/data:rw \ -v ~/docker/isaac-sim/documents:/root/Documents:rw \ -v /home/ubuntu/Documents/Isaac_files:/root/Documents/Isaac_files \ -v /tmp/.X11-unix:/tmp/.X11-unix \ -e DISPLAY=$DISPLAY \ -v /dev/dri:/dev/dri \ isaac-sim-ros2:4.2.0
- X11 Forwarding: This enables graphical interfaces to be displayed.
- Display Variable: Ensures ROS2 and Isaac Sim GUI work correctly.
Loading the Warehouse Scene
- Launch Isaac Sim within the container by running:
./runheadless.webrtc.sh
(you can run ./runheadless.native.sh if you want to load the interface with Omniverse Streaming Client). - In the Isaac Sim interface, navigate to the Assets tab.
- Load the scene Warehouse_with_forklifts. This will set up the virtual environment with a forklift.
- Add a new forklift, in this case the asset “forklift_c”
Attaching a Camera to the Forklift
- Add a camera to the scene by dragging a camera object from the create tab into the scene.
- Place the camera under the forklift’s hierarchy, specifically inside the “lift” prim. This ensures the camera moves along with the forklift’s lift mechanism.
- Configure the camera’s position and orientation to face forward, capturing the view directly in front of the forklift.
- Save the configuration to ensure the camera placement is preserved for future use.
Creating the Action Graph
Action graph to move the forklift via keyboard
To enable keyboard control of the forklift within Isaac Sim, you’ll need to configure an Action Graph. This graph links user input (keyboard) to the forklift’s motion and steering mechanisms, simulating Ackermann steering for realistic vehicle control.
For detailed instructions on creating this graph, refer to our blog post Isaac Sim Integration with ROS 2, specifically the section Controlling a Four-Wheeled Forklift with Ackermann Steering. (https://lnkd.in/dEnJZqbz)
Creating the Action Graph to Publish Images
To enable the camera mounted on the forklift to capture images and publish them to a ROS2 topic (/rgb), you need to configure an Action Graph in Isaac Sim. This graph links the camera to ROS2 communication nodes.
Steps to Create the Action Graph
- Open the Action Graph Editor:
- In Isaac Sim, navigate to the menu and open the Action Graph editor.
- Create a new Action Graph for this purpose.
- Add the Required Nodes: Create and connect the following nodes as shown in the provided layout:
- On Playback Tick: Triggers the graph on every simulation tick.
- Isaac Run One Simulation Frame: Ensures the simulation advances by one frame for real-time updates.
- ROS2 Context: Initializes the ROS2 environment and establishes communication.
- Isaac Create Render Product: Captures images from the camera mounted on the forklift.
- ROS2 Camera Helper: Configures the camera properties and sets the ROS2 topic namespace.
- ROS2 Publish Image: Publishes the captured images to the /rgb topic in ROS2.
Detailed Explanation of Nodes
- On Playback Tick:
- This node continuously triggers the graph during simulation playback, ensuring the image publishing is real-time.
- Isaac Run One Simulation Frame:
- Advances the simulation by one frame for each tick, keeping the data flow synchronized.
- ROS2 Context:
- Establishes a ROS2 environment, allowing other nodes in the graph to interact with ROS2.
- Isaac Create Render Product:
- Captures images from the camera you mounted on the forklift.
- Set the camera path and camera resolution.
- ROS2 Camera Helper:
- Configures the camera’s attributes, such as frame rate and field of view, for ROS2 integration.
- Define the namespace and ensure the topic name is /rgb.
- ROS2 Publish Image:
- Takes the captured image from the camera and publishes it to the /rgb topic, making it available for processing by ROS2 nodes.
- Verify and Save:
- Once the nodes are connected and configured, save the Action Graph.
- Run the simulation and monitor the /rgb topic in ROS2 to verify that images are being published correctly.
For a more detailed view refer to Appendix 1: Action Graph.
Create a ROS2 package
Navigate to the root directory of the container using the command: cd ..
Once in the root directory, create a new folder named ros2_ws to serve as your ROS2 workspace. Inside this folder, create another folder named src. These directories will organize the files for your ROS2 package.
Next, move into the src directory and run the following command to create a new ROS2 package named yolov8_detector. This package will handle the object detection tasks:
mkdir ros2_ws cd ros2_ws mkdir src cd src ros2 pkg create --build-type ament_python yolov8_detector
--build-type ament_python
: Specifies that the package will use Python as its primary language.yolov8_detector
: The name of the package, which will be used throughout the project.
The previous step created a new directory named yolov8_detector with the following structure:
yolov8_detector/ ├── package.xml ├── setup.py ├── resource │ └── yolov8_detector └── yolov8_detector ├── __init__.py
Adding the ROS2 Node for Image Processing
Inside the yolov8_detector/yolov8_detector directory, you need to create the Python file that will handle capturing images published by Isaac Sim. This file will also perform object detection using the YOLOv8 model.
Create the Node File
In the src directory execute the following command to create a new Python file:
nano yolov8_detector/yolov8_detector/yolov8_node.py
Add the Node Code
Inside the yolov8_node.py file, paste the following code. This script listens to the /rgb topic in Isaac Sim, processes the camera frames using YOLOv8, and publishes the detection results to a new topic named /camera/detections:
import rclpy from rclpy.node import Node from sensor_msgs.msg import Image from cv_bridge import CvBridge import cv2 from ultralytics import YOLO class Yolov8Detector(Node): def __init__(self): super().__init__('yolov8_detector') self.subscription = self.create_subscription( Image, '/rgb', # The topic where Isaac Sim publishes camera frames self.listener_callback, 10) self.publisher = self.create_publisher(Image, '/camera/detections', 10) self.bridge = CvBridge() self.model = YOLO('~/your_path/yolov8n.pt') # Path to your YOLOv8 model def listener_callback(self, msg): # Convert ROS Image message to OpenCV format cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8') # Perform object detection results = self.model(cv_image) # Draw bounding boxes on the image annotated_frame = results[0].plot() # Convert back to ROS Image message detection_msg = self.bridge.cv2_to_imgmsg(annotated_frame, encoding='bgr8') detection_msg.header = msg.header # Retain original message header self.publisher.publish(detection_msg) def main(args=None): rclpy.init(args=args) yolov8_detector = Yolov8Detector() rclpy.spin(yolov8_detector) yolov8_detector.destroy_node() rclpy.shutdown() if __name__ == '__main__': main()
- Topics: The /rgb topic is where Isaac Sim publishes the camera frames. Ensure this matches the topic name configured in Isaac Sim.
- YOLO Model: Update the path ~/your_path/yolov8n.pt with the location of your YOLOv8 model file. (You can download the model weights at the following link: https://github.com/ultralytics/assets/releases/download/v8.2.0/yolov8n.pt)
- Output Topic: The processed frames with bounding boxes are published to /camera/detections, making them accessible for visualization in RViz2 or other tools.
Save the file and exit the editor. This step completes the setup for capturing and processing images from Isaac Sim.
Configuring the setup.py File
The setup.py file is a crucial component of your ROS2 package. It serves as the build script, specifying metadata about the package, its dependencies, and its executable entry points. This file allows ROS2 tools, such as colcon, to properly build, install, and manage your package.
Steps to Edit the setup.py File
- Navigate to the ros2_wc/src directory Run the following command to open the setup.py file for editing:
nano yolov8_detector/setup.py
- Paste the Configuration Replace the contents of the file with the following code:
from setuptools import find_packages, setup package_name = 'yolov8_detector' setup( name=package_name, version='0.0.0', packages=['yolov8_detector'], data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ], install_requires=['setuptools', 'rclpy', 'cv_bridge', 'ultralytics'], zip_safe=True, maintainer='root', maintainer_email='[email protected]', description='TODO: Package description', license='TODO: License declaration', tests_require=['pytest'], entry_points={ 'console_scripts': [ 'yolov8_node = yolov8_detector.yolov8_node:main' ], }, )
- name: Specifies the name of the package (yolov8_detector).
- version: Defines the current version of the package (0.0.0).
- packages: Includes the Python modules or packages to be installed (yolov8_detector).
- data_files: Lists files such as package.xml and resource files required for ROS2 integration.
- install_requires: Declares the Python dependencies needed for the package, including rclpy, cv_bridge, and ultralytics.
- entry_points: Maps console scripts to their entry points, making the yolov8_node executable via ROS2 commands.
Building the ROS2 Package and Verifying Installation
Using colcon
What is colcon?
colcon (short for “collective construction”) is a command-line tool used to build, test, and manage ROS2 workspaces. It automates the process of compiling packages, resolving dependencies, and generating necessary files for executing ROS2 nodes.
Build the Package
Navigate to the root of the ROS2 workspace (/ros2_ws) and run the following command:
colcon build --packages-select yolov8_detector
–packages-select yolov8_detector: This option tells colcon to build only the yolov8_detector package instead of all packages in the workspace.
What happens during the build?
- colcon reads the setup.py file to understand the package configuration.
- Dependencies listed in setup.py are checked and resolved.
- Compiled files and installation directories are generated in the install folder of your workspace.
Sourcing the Workspace
After the build process completes, you need to source the workspace:
source install/setup.bash
What does this command do?
- It sets up the environment so ROS2 can locate the built package.
- It updates the ROS_PACKAGE_PATH, ensuring tools like ros2 run and ros2 launch can find your package and its nodes.
Verifying the Package
Run the following command to list all packages in the workspace and filter for yolov8_detector:
ros2 pkg list | grep yolov8_detector
ros2 pkg list: Lists all available ROS2 packages in the current environment.
grep yolov8_detector: Filters the output to display only the line containing the package name yolov8_detector.
Expected Output:
If everything is set up correctly, you should see: yolov8_detector
Launching the Full System for Object Detection and Visualization
To fully utilize the system you’ve set up, you will need three terminal tabs, each connected to the Isaac Sim container. Here’s how to proceed:
Access the Container in Each Terminal
In each terminal, run the following command to access the running Docker container:
docker exec -it isaac-sim bash
This command opens an interactive session inside the container where you can run ROS2 commands.
First Terminal: Launching the Object Detection Node
Run the following command from ./ros2_ws to execute the object detection node:
ros2 run yolov8_detector yolov8_node
If the above does not work, run source install/setup.bash again and repeat the previous command
What Happens Here?
- The yolov8_node starts listening to the /rgb topic, where images from the forklift camera are published.
- YOLOv8 processes the images, detects objects, and publishes annotated frames to the /camera/detections topic.
- Logs of detections (e.g., detected objects and their confidence scores) will be displayed in this terminal.
Second Terminal: Controlling the Forklift
In the second terminal, execute this command to enable keyboard control of the forklift:
ros2 run teleop_twist_keyboard teleop_twist_keyboard
Check out this setup in our previous blog post: Isaac Sim Integration with ROS 2.
What Happens Here?
- This launches a ROS2 node for keyboard teleoperation.
- Using the keyboard, you can send velocity and steering commands to move the forklift in the virtual warehouse.
- Ensure the ROS2 topic for teleoperation matches the one configured in Isaac Sim’s Action Graph for forklift control.
Launching the Full System for Object Detection and Visualization
To fully utilize the system you’ve set up, you will need three terminal tabs, each connected to the Isaac Sim container. Here’s how to proceed:
Access the Container in Each Terminal
In each terminal, run the following command to access the running Docker container:
docker exec -it isaac-sim bash
This command opens an interactive session inside the container where you can run ROS2 commands.
First Terminal: Launching the Object Detection Node
Run the following command to execute the object detection node:
ros2 run yolov8_detector yolov8_node
What Happens Here?
- The yolov8_node starts listening to the /rgb topic, where images from the forklift camera are published.
- YOLOv8 processes the images, detects objects, and publishes annotated frames to the /camera/detections topic.
- Logs of detections (e.g., detected objects and their confidence scores) will be displayed in this terminal.
Second Terminal: Controlling the Forklift
In the second terminal, execute this command to enable keyboard control of the forklift:
ros2 run teleop_twist_keyboard teleop_twist_keyboard
What Happens Here?
- This launches a ROS2 node for keyboard teleoperation.
- Using the keyboard, you can send velocity and steering commands to move the forklift in the virtual warehouse.
- Ensure the ROS2 topic for teleoperation matches the one configured in Isaac Sim’s Action Graph for forklift control.
Keyboard Shortcuts:
- Use W, A, S, D for forward, left, backward, and right movements.
- Follow the on-screen instructions for more controls.
Third Terminal: Visualizing in RViz2
Run the following command to launch RViz2:
ros2 run rviz2 rviz2
What is RViz2?
RViz2 is a 3D visualization tool for ROS2 that enables real-time monitoring of sensor data, robot states, and more. It provides a graphical interface for visualizing topics, making it ideal for debugging and monitoring.
What Happens Here?
- RViz2 will display the live camera feed from the forklift.
- You will see bounding boxes overlaid on the camera images, representing the objects detected by YOLOv8.
Add Topics for Visualization
- Access the “Add” Menu:
- Locate and click the Add button, typically found in the left panel or toolbar of the RViz2 interface.
- Select “By Topic”:
- In the popup menu, click By Topic to browse available ROS2 topics.
- Add the /rgb Topic:
- Navigate to the /rgb topic in the list.
- Under this topic, select Image.
- Click OK to add the topic to RViz2.
- This displays the original real-time feed captured by the forklift’s front-facing camera in RViz2.
- Add the /camera/detections Topic:
- Repeat the process, but this time navigate to the /camera/detections topic.
- Again, select Image and click OK.
- This displays the annotated frames from YOLOv8, showing the bounding boxes and detection results in real-time.
Now that everything is set up, it’s time to bring the system to life by controlling the forklift and observing the real-time detections in RViz2.
Appendix 1: Action Graph
Original image:
Closeups: