ROS 2 Python Custom Messages#
Note
ROS 2 Python Custom Messages with Isaac Sim is fully supported on Linux. On Windows (WSL), this workflow is not supported.
Learning Objectives#
In this example, you learn how to use ROS 2 rclpy
Python interface with Isaac Sim for a custom message.
Getting Started#
Prerequisite
Basic understanding of building ROS 2 packages.
Using Custom Messages with Python#
For using rclpy
with Isaac Sim the packages must be built with Python3.11
. You can create your own package and build it with the ROS 2 workspace
Isaac Sim only supports Python 3.11. Packages built can be used directly with rclpy
in Isaac Sim, if they are built with Python 3.11.
For demonstrating the workflow, the tutorial uses a custom_message
package, which is a part of the Isaac Sim ROS Workspace repository.
This repository contains a custom message under custom_message/msg/SampleMsg.msg
with the following definition:
std_msgs/String my_string
int64 my_num
To build your own ROS 2 custom message packages for use with Isaac Sim, you can place the package under humble_ws/src
or jazzy_ws/src
in your Isaac Sim ROS Workspace
folder. Then run ./build_ros.sh
and source your workspaces before running Isaac Sim.
Ensure you have completed the steps in the ROS Installation Guide following the installation track for custom packages.
Run Isaac Sim from the same terminal, the sourced workspace contains the minimal ROS 2 dependencies needed to enable the ROS 2 bridge and the
custom_message
package, which contains our sample message.
Using the custom_message
package with Python in Isaac Sim:
Launch Isaac Sim from the sourced terminal containing the custom_message
package.
Open the Script Editor and type:
import rclpy
from custom_message.msg import SampleMsg
# Create message
sample_msg = SampleMsg()
# assign data in the string part and integer part of the message
sample_msg.my_string.data = "hello from Isaac Sim!"
sample_msg.my_num = 23
print("Message assignment completed!")
Press Run and verify that the Message assignment completed
is logged on your console. This indicates that the message import and interaction was successful.
You can use a standalone Python script to enable the ROS 2 bridge and import your custom_message
.
Navigate to your Isaac Sim installation directory and create a file named ros2_custom_message.py
, paste the following content into it:
import carb
from isaacsim import SimulationApp
simulation_app = SimulationApp({"renderer": "RayTracedLighting", "headless": True})
import omni
from isaacsim.core.utils.extensions import enable_extension
# enable ROS2 bridge extension
enable_extension("isaacsim.ros2.bridge")
# Make the rclpy imports
import rclpy
from custom_message.msg import SampleMsg
# Create message
sample_msg = SampleMsg()
# assign data in the string part and integer part of the message
sample_msg.my_string.data = "hello from Isaac Sim!"
sample_msg.my_num = 23
print("Message assignment completed!")
Make sure that your ROS 2 workspace with the custom_message
package is sourced in the same terminal and that you are in the right directory, which contains ./python.sh
.
Run this script:
./python.sh ros2_custom_message.py
Verify that Message assignment completed
is logged on your console. This indicates that the message import and interaction was successful.
Summary#
This tutorial covered the following topics:
Building a ROS 2 custom message package with
Python3.11
Using the custom message with
rclpy
in Isaac SimOverview of steps to build and use your own custom message package with
rclpy
and Isaac Sim
Next Steps#
Continue on to the next tutorial in our ROS2 Tutorials series, ROS 2 Python Custom OmniGraph Node.