isaac_ros_pynitros
Source code on GitHub.
Creating PyNITROS-Accelerated Nodes
The following steps outline how to create PyNITROS-accelerated nodes using the PyNITROS API. This example
demonstrates how to use PyNITROS to publish and subscribe image messages. PyNITROS also supports tensor list messages,
which can be used in a similar manner. You can find the source code of this example under the isaac_ros_pynitros/examples
directory.
Instantiate the
PyNitrosSubscriber
. Developers can instantiate thePyNitrosSubscriber
class with the following five parameters:ROS node
NITROS Bridge message type
NITROS Bridge message topic name
raw ROS message topic name
enable ROS subscribe flag
After instantiation, use the
create_subscription
function to create a subscription with a user-defined callback function.pynitros_subscriber = PyNitrosSubscriber(Node, NitrosBridgeImage, "pynitros_image", "pynitros_image_raw", enable_ros_subscribe=False)
pynitros_subscriber.create_subscription(sub_callback)
Create the
PyNitrosPublisher
by specifying ROS node, NITROS Bridge message type, NITROS Bridge topic name, and raw ROS topic name respectively.pynitros_publisher = PyNitrosPublisher(Node, NitrosBridgeImage, "pynitros_image", "pynitros_image_raw")
Create the PyNITROS image builder. This builder will create a memory pool with a number of buffers to hold the IPC GPU data of messages pending to publish. To instantiate the builder, you need to specify the number of buffers and timeout for reclaiming the buffer back to the pool.
pynitros_image_builder = PyNitrosImageBuilder(num_buffer (optional), timeout (optional))
When a subscribed message arrives, the callback function is triggered with a
PyNITROSView
of the message. You can convert this view to another data type of your choice, such as a PyTorch tensor, by passing inpynitros_image_view
into thetorch.as_tensor()
function:def sub_callback(pynitros_image_view): # (Optional) If user has async GPU operations in the fly, pass stream back to the view stream = cudart.cudaStreamCreate() pynitros_image_view.set_stream(stream) # Get data as tensor, or any other data type supports __cuda_array_interface__ image_tensor = torch.as_tensor(pynitros_image_view, dtype=torch.uint8, device=gpu)
After processing the received image, pass the device pointer of the output and metadata into the
PyNitrosBuilder
build function. This generates aNitrosBridgeImage
that can then be published using thePyNitrosPublisher
. If theenable_ros_publish
flag is set toTrue
, the publisher also sends the raw image (that is, anImage
message) to the second topic specified during instantiation.built_image = pynitros_image_builder.build(image_data_ptr, image_height, image_width, image_step, image_encoding, image_header, device_id=0, enable_ros_publish=False)
Publish the built image using the publisher:
pynitros_publisher.publish(built_image)
Note
PyNITROS requires the permission of PTRACE_ATTACH
for IPC. You can
set the ptrace_scope
by running the following command:
echo 0 | sudo tee /proc/sys/kernel/yama/ptrace_scope
Quickstart
This quickstart uses the image_forward
node built with PyNITROS to demonstrate the zero-copy inter-op between PyNITROS nodes.
Set Up Development Environment
Set up your development environment by following the instructions in getting started.
Clone
isaac_ros_common
under${ISAAC_ROS_WS}/src
.cd ${ISAAC_ROS_WS}/src && \ git clone -b release-3.2 https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common.git isaac_ros_common
Download Quickstart Assets
Download quickstart data from NGC:
Make sure required libraries are installed.
sudo apt-get install -y curl jq tar
Then, run these commands to download the asset from NGC:
NGC_ORG="nvidia" NGC_TEAM="isaac" PACKAGE_NAME="isaac_ros_pynitros" NGC_RESOURCE="isaac_ros_pynitros_assets" NGC_FILENAME="quickstart.tar.gz" MAJOR_VERSION=3 MINOR_VERSION=2 VERSION_REQ_URL="https://catalog.ngc.nvidia.com/api/resources/versions?orgName=$NGC_ORG&teamName=$NGC_TEAM&name=$NGC_RESOURCE&isPublic=true&pageNumber=0&pageSize=100&sortOrder=CREATED_DATE_DESC" AVAILABLE_VERSIONS=$(curl -s \ -H "Accept: application/json" "$VERSION_REQ_URL") LATEST_VERSION_ID=$(echo $AVAILABLE_VERSIONS | jq -r " .recipeVersions[] | .versionId as \$v | \$v | select(test(\"^\\\\d+\\\\.\\\\d+\\\\.\\\\d+$\")) | split(\".\") | {major: .[0]|tonumber, minor: .[1]|tonumber, patch: .[2]|tonumber} | select(.major == $MAJOR_VERSION and .minor <= $MINOR_VERSION) | \$v " | sort -V | tail -n 1 ) if [ -z "$LATEST_VERSION_ID" ]; then echo "No corresponding version found for Isaac ROS $MAJOR_VERSION.$MINOR_VERSION" echo "Found versions:" echo $AVAILABLE_VERSIONS | jq -r '.recipeVersions[].versionId' else mkdir -p ${ISAAC_ROS_WS}/isaac_ros_assets && \ FILE_REQ_URL="https://api.ngc.nvidia.com/v2/resources/$NGC_ORG/$NGC_TEAM/$NGC_RESOURCE/\ versions/$LATEST_VERSION_ID/files/$NGC_FILENAME" && \ curl -LO --request GET "${FILE_REQ_URL}" && \ tar -xf ${NGC_FILENAME} -C ${ISAAC_ROS_WS}/isaac_ros_assets && \ rm ${NGC_FILENAME} fi
Build isaac_ros_pynitros
Launch the Docker container using the
run_dev.sh
script:cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh
Install the prebuilt Debian package:
sudo apt-get update
sudo apt-get install -y ros-humble-isaac-ros-pynitros
Clone this repository under
${ISAAC_ROS_WS}/src
:cd ${ISAAC_ROS_WS}/src && \ git clone -b release-3.2 https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_nitros.git isaac_ros_nitros
Launch the Docker container using the
run_dev.sh
script:cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh
Use
rosdep
to install the package’s dependencies:sudo apt-get update
rosdep update && rosdep install --from-paths ${ISAAC_ROS_WS}/src/isaac_ros_nitros/isaac_ros_pynitros --ignore-src -y
Build the package from source:
cd ${ISAAC_ROS_WS}/ && \ colcon build --symlink-install --packages-up-to isaac_ros_pynitros --base-paths ${ISAAC_ROS_WS}/src/isaac_ros_nitros/isaac_ros_pynitros
Source the ROS workspace:
Note
Make sure to repeat this step in every terminal created inside the Docker container.
Because this package was built from source, the enclosing workspace must be sourced for ROS to be able to find the package’s contents.
source install/setup.bash
Run Launch File
Set the
ptrace_scope
:
echo 0 | sudo tee /proc/sys/kernel/yama/ptrace_scope
Run the following launch files to spin up a demo of this package:
cd /workspaces/isaac_ros-dev && \ ros2 launch isaac_ros_pynitros isaac_ros_pynitros_quickstart.launch.py rosbag_path:=${ISAAC_ROS_WS}/isaac_ros_assets/isaac_ros_pynitros/quickstart.bag
Attach a second terminal to the Docker container:
cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh -d ${HOME}/workspaces
Visualize the output topic
/pynitros2_output_msg_ros
in RViz:cd /workspaces/isaac_ros-dev/ && \ rviz2
Try More Examples
To continue your exploration, explore the following examples:
API Reference
- class PyNitrosPublisher(node, nitros_bridge_msg_type, nitros_bridge_topic_name, raw_ros_topic_name)
Publisher to publish PyNITROS messages.
- Parameters:
node (rclpy.node.Node) – The ROS node.
nitros_bridge_msg_type (MsgType) – The type of NITROS Bridge message the publisher will publish.
nitros_bridge_topic_name (str) – The name of NITROS Bridge topic the publisher will publish to.
raw_ros_topic_name (str) – The name of raw topic the publisher will publish to when applicable.
- publish(nitros_bridge_msg)
Publish a PyNITROS message.
- Parameters:
nitros_bridge_msg (isaac_ros_nitros_bridge_interfaces.msg) – The NITROS Bridge message to publish.
- Returns:
None
- class PyNitrosSubscriber(node, message_type, sub_topic_name, enable_ros_subscribe)
Subscriber subscribe to PyNITROS messages.
- Parameters:
node (rclpy.node.Node) – The ROS node.
message_type (MsgType) – The type of NITROS Bridge message the subscriber will subscribe to.
sub_topic_name (str) – The name of the topic the subscriber will subscribe to.
enable_ros_subscribe (bool) – A flag to enable subscribing to raw message exclusively.
- create_subscription(input_callback)
Create a subscription with a user-defined callback function. The callback function will be triggered with a PyNITROS view of the arrived message.
- Parameters:
input_callback – A user-defined callback for the subscriber.
- Returns:
None
- class PyNITROSMessageFilter(node, subscribers, synchronizer_type, callback, queue_size=10, slop=0.1)
Message filters to synchronize multiple NITROS Bridge or ROS2 raw messages.
- Parameters:
node (rclpy.node.Node) – The ROS node.
subscribers (list) – A list of PyNITROS or
rclpy
subscribers.synchronizer_type (SynchronizerType) – The type of synchronizer to use. Select from
TimeSynchronizer
orApproximateTimeSynchronizer
callback (Callable) – A user-defined callback for the message filter.
queue_size (int) – The size of the queue for the message filter.
slop (float) – The delay (in seconds) with which messages can be synchronized.
- class PyNitrosImageBuilder(num_buffer, timeout)
A class to build PyNITROS images.
- Parameters:
num_buffer (int) – The number of CUDA IPC buffers to allocate.
timeout (int) – The timeout for reclaiming the buffer back to the pool.
- build(image_data, image_height, image_width, image_step, image_encoding, image_header, device_id, enable_ros_publish, event=None)
Build a PyNITROS image.
- Parameters:
image_data (int) – Device data pointer of the image.
image_height (int) – Height of the image.
image_width (int) – Width of the image.
image_step (int) – Step of the image.
image_encoding (str) – Encoding of the image.
image_header (str) – Header of the image.
device_id (int) – Device ID on which the image data is stored.
enable_ros_publish (bool) – A flag to enable publishing ROS message in the meantime.
event (cuda.cudart.cudaEvent_t) – CUDA event to synchronize on.
- Returns:
Tuple of the built NITROS Bridge image, and the raw ROS image if
enable_ros_publish
is set toTrue
.- Return type:
tuple
- class PyNitrosTensorListBuilder(num_buffer, timeout)
A class to build PyNITROS tensor list.
- Parameters:
num_buffer (int) – The number of CUDA IPC buffers to allocate.
timeout (int) – The minimum time allows reclaiming the buffer back to the pool.
- build_tensor(tensor_data, tensor_name, tensor_shape, tensor_data_type)
Build a PyNITROS tensor.
- Parameters:
tensor_data (int) – Device data pointer of the tensor.
tensor_name – Name of the tensor.
tensor_shape (list) – Shape of the tensor.
tensor_data_type (int) – Data type of the tensor.
- Returns:
The built NITROS Bridge tensor.
- Return type:
NitrosBridgeTensor
- build(built_tensors, tensors_header, device_id, enable_ros_publish, event=None)
Build a PyNITROS tensor list.
- Parameters:
built_tensors (int) – Built tensors returned by
build_tensor
function.tensor_header (str) – Header of the tensor list.
device_id (int) – Device ID on which the tensor list is stored.
enable_ros_publish (bool) – A flag to enable publishing ROS message in the meantime.
event (cuda.cudart.cudaEvent_t) – CUDA event to synchronize on.
- Returns:
Tuple of the built NITROS Bridge tensor list, and the raw ROS tensor list if
enable_ros_publish
is set toTrue
.- Return type:
tuple
- class PyNitrosImageView
A class to view PyNITROS image.
- get_size_in_bytes()
Get the size of the PyNITROS image in bytes.
- Returns:
The size of the PyNITROS image in bytes.
- Return type:
int
- get_width()
Get the width of the PyNITROS image.
- Returns:
The width of the PyNITROS image.
- Return type:
int
- get_height()
Get the height of the PyNITROS image.
- Returns:
The height of the PyNITROS image.
- Return type:
int
- get_stride()
Get the stride of the PyNITROS image.
- Returns:
The stride of the PyNITROS image.
- Return type:
int
- get_buffer()
Get the device data pointer of the PyNITROS image.
- Returns:
The device data pointer of the PyNITROS image.
- Return type:
int
- get_encoding()
Get the encoding of the PyNITROS image.
- Returns:
The encoding of the PyNITROS image.
- Return type:
str
- get_frame_id()
Get the frame ID of the PyNITROS image.
- Returns:
Frame ID of the PyNITROS image.
- Return type:
str
- get_timestamp_seconds()
Get the seconds from the PyNITROS image header.
- Returns:
Seconds from the PyNITROS image header.
- Return type:
int
- get_timestamp_nanoseconds()
Get the nanoseconds from the PyNITROS image header.
- Returns:
Nanoseconds from the PyNITROS image header.
- Return type:
int
- set_stream(stream)
If the subscriber callback contains asynchronous CUDA operations, set the stream for the PyNITROS image view.
- Parameters:
stream (cuda.cudart.cudaStream_t) – CUDA stream.
- class PyNitrosTensorListView
A class to view PyNITROS tensor list.
- get_size_in_bytes()
Get the total size of the PyNITROS tensor list in bytes.
- Returns:
Total size of the PyNITROS tensor in bytes.
- Return type:
int
- get_buffer()
Get the device pointer of the first PyNITROS tensor data.
- Returns:
The device pointer of the first PyNITROS tensor.
- Return type:
int
- get_tensor_count()
Get the number of tensors in the PyNITROS tensor list.
- Returns:
Number of tensors in the PyNITROS tensor list.
- Return type:
int
- get_named_tensor(name)
Get the tensor with the specified name from the PyNITROS tensor list.
- Parameters:
name (str) – The name of the tensor.
- Returns:
The tensor with the specified name.
- Return type:
- get_all_tensors()
Get all the tensors in the PyNITROS tensor list.
- Returns:
All the tensors in the PyNITROS tensor list.
- Return type:
list
- get_frame_id()
Get the frame ID of the PyNITROS tensor.
- Returns:
Frame ID of the PyNITROS tensor.
- Return type:
str
- get_timestamp_seconds()
Get the seconds from the PyNITROS image header.
- Returns:
Seconds from the PyNITROS image header.
- Return type:
int
- get_timestamp_nanoseconds()
Get the nanoseconds from the PyNITROS image header.
- Returns:
Nanoseconds from the PyNITROS image header.
- Return type:
int
- set_stream(stream)
If the subscriber callback contains asynchronous CUDA operations, set the stream for the PyNITROS image view.
- Parameters:
stream (cuda.cudart.cudaStream_t) – CUDA stream.
- class PyNitrosTensorView
A class to view PyNITROS tensors.
- get_name()
Get the name of the PyNITROS tensor.
- Returns:
The name of the PyNITROS tensor.
- Return type:
str
- get_buffer()
Get the device pointer of the PyNITROS tensor data.
- Returns:
The device pointer of the PyNITROS tensor.
- Return type:
int
- get_rank()
Get the rank of the PyNITROS tensor.
- Returns:
The rank of the PyNITROS tensor.
- Return type:
int
- get_element_count()
Get the element count of the PyNITROS tensor.
- Returns:
The element count of the PyNITROS tensor.
- Return type:
int
- get_tensor_size()
Get the size in bytes of the PyNITROS tensor.
- Returns:
The size of the PyNITROS tensor.
- Return type:
int
- get_shape()
Get the shape of the PyNITROS tensor.
- Returns:
The shape of the PyNITROS tensor.
- Return type:
list
- get_element_type()
Get the data type of the PyNITROS tensor.
- Returns:
The data type of the PyNITROS tensor.
- Return type:
str
- get_bytes_per_element()
Get the element size in bytes of the PyNITROS tensor.
- Returns:
The element size of the PyNITROS tensor in bytes.
- Return type:
int