The QRB ROS Camera is a ROS package to publish the images from Qualcomm CSI and GMSL cameras. It provides:
- Concurrent multiple streams output support.
- Composable ROS node support.
- Zero-Copy transport powered by QRB ROS Transport.
- Only support outputs in NV12 format,limited by the Camera Service.
The qrb_ros_camera
is a ROS 2 package. It creates an image publisher with qrb_ros_transport for zero-copy transport. It supports node composition, making it possible to improve performance using ROS intra-process communication.
The qrb_camera
is a C++ library, it provides APIs to qrb_ros_camera
for querying images from lower layer Camera Service
and CamX
libraries. It includes 2 modules:
- The module
camera_manager
used to manage camera stream, which enables multiple stream support. - The module
camera_client
used to callCamera Service
apis to manage camera streams.
The qrb_ros_transport
is a ROS 2 package, it supports zero-copy image transport with Linux DMA buffer and implements ROS type adaption, make it compatible with both intra- and inter-process communication.
The Camera Service
is Qualcomm multimedia framework, it exports APIs for accessing Qualcomm multimedia hardware.
The CamX
provides the foundation for image capture, processing, and management on Qualcomm-powered devices.
Interface | Name | Type | Description |
---|---|---|---|
Publisher | /cam${camera_id}_${stream_name} | sensor_msgs/msg/Image | output image |
/cam${camera_id}_camera_info | sensor_msgs/msg/CameraInfo | camera information |
Name | Type | Description | Default Value |
---|---|---|---|
camera_id | int64 | The camera device ID | 0 |
stream_size | uint64 | Count of camera stream | 1 |
stream_name | string[] | camera stream names | ["stream1"] |
${stream_name}.width | uint32 | image width | 1920 |
${stream_name}.height | uint32 | image height | 1080 |
${stream_name}.fps | uint32 | output image frequency(Hz) | 30 |
camera_info_path | string | Camera metadata file path | config/camera_info_imx577.yaml |
Note
The parameter values should be set accroding to the actual camera hardware capabilities.
Function | Parameters | Description |
---|---|---|
int create_camera(CameraType type, uint32_t camera_id) | type: camera type, camera_id: camera id | Creates a camera and returns the camera index on success. |
bool set_camera_parameter(int index, CameraConfigure & param) | index: camera index, param: camera parameters | Returns true when the camera parameters are set successfully. |
bool start_camera(int index) | index: camera index | Starts the camera. Returns true when started successfully. |
void stop_camera(int index) | index: camera index | Stop the camera |
bool register_callback(int index, ImageCallback image_cb, PointCloudCallback point_cloud_cb) | index: camera index,Image_cb: image callback,Point_cloud_cb: point cloud msg callback | Registers the callback for image and point cloud messages. |
Note
The parameter values should be set accroding to the actual camera hardware capabilities.
Important
PREREQUISITES: The following steps need to be run on Qualcomm Ubuntu and ROS Jazzy.
Reference Install Ubuntu on Qualcomm IoT Platforms and Install ROS Jazzy to setup environment.
For Qualcomm Linux, please check out the Qualcomm Intelligent Robotics Product SDK documents.
Add Qualcomm IOT PPA for Ubuntu:
sudo add-apt-repository ppa:ubuntu-qcom-iot/qcom-noble-ppa
sudo add-apt-repository ppa:ubuntu-qcom-iot/qirp
sudo apt update
Install Debian package:
sudo apt install ros-jazzy-qrb-ros-camera
source /opt/ros/jazzy/setup.bash
ros2 launch qrb_ros_camera qrb_ros_camera_launch.py
When using this launch script, it will use the default parameters:
parameters=[{
'camera_id': 0,
'stream_size': 1,
'stream_name': ["stream1"],
'stream1':{
'height':1080,
'width':1920,
'fps':30,
},
'camera_info_path': os.path.join(
get_package_share_directory('qrb_ros_camera'),
'config', 'camera_info_imx577.yaml'),
}]
It opens camera 0
, with 1
stream, using a resolution of 1920 x 1080
, and outputs image at 30
Hz.
The output for these commands:
[INFO] [launch]: All log files can be found below /home/ubuntu/.ros/log/2025-07-11-08-33-27-770692-ubuntu-13833
[INFO] [launch]: Default logging verbosity is set to INFO
/opt/ros/jazzy/share/qrb_ros_camera/config/camera_info_imx577.yaml
[INFO] [component_container_mt-1]: process started with pid [788455]
[component_container_mt-1] [INFO] [1738523640.352029048] [my_container]: Load Library: /opt/ros/jazzy/lib/libcamera_node.so
[component_container_mt-1] [INFO] [1738523640.391541131] [my_container]: Found class: rclcpp_components::NodeFactoryTemplate<qrb_ros::camera::CameraNode>
[component_container_mt-1] [INFO] [1738523640.391636496] [my_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<qrb_ros::camera::CameraNode>
[component_container_mt-1] [INFO] [1738523640.407687277] [cam0_node]: QRB Camera Node statrt
[component_container_mt-1] [INFO] [1738523640.408260298] [cam0_node]: load camera intrinsic param
[component_container_mt-1] [INFO] [1738523640.422302798] [cam0_node]: system time: 263304942972212 ros time: 1738523640422300871 time offset: 1738260335479328659 ns
[component_container_mt-1] [INFO] [1738523640.424454465] [cam0_node]: QRB Camera Node init success
...
Then you can check ROS topics or view image with the topic /cam${camera_id}_${stream_name}
in RVIZ or RQT.
ros2 topic list
/cam0_stream1
/cam0_camera_info
By using the stream_size
and stream_name
parameters, you can configure multiple streams for one camera.
parameters=[{
'camera_id': 0,
'stream_size': 2,
'stream_name': ["stream1", "stream2"],
'stream1':{
'width':1920,
'height':1080,
'fps':30,
},
'stream2':{
'width':1080,
'height':720,
'fps':60,
},
'camera_info_path': os.path.join(
get_package_share_directory('qrb_ros_camera'),
'config', 'camera_info_imx577.yaml'),
}]
The qrb_ros_camera
supports directly sharing image dmabuf_fd
between nodes, which can avoid image data memory copy with DDS.
For detail about this feature, see https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Composition.html
We recommend using launch
to compose multiple nodes:
def generate_launch_description():
container = ComposableNodeContainer(
name='my_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
ComposableNode(
package='qrb_ros_camera',
plugin='qrb_ros::camera::CameraNode',
name='camera_node',
parameters=[{
# ...
}]
),
ComposableNode(
package='qrb_ros_camera',
plugin='qrb_ros::camera::TestNode',
name='sub_node',
)
],
output='screen',
)
return launch.LaunchDescription([container])
Install dependencies
sudo apt install ros-jazzy-qrb-ros-transport-image-type
Download the source code and build with colcon
source /opt/ros/jazzy/setup.bash
git clone https://github.com/qualcomm-qrb-ros/qrb_ros_camera.git
colcon build
Run and debug
source install/setup.bash
ros2 launch qrb_ros_camera qrb_ros_camera_launch.py
We love community contributions! Get started by reading our CONTRIBUTING.md.
Feel free to create an issue for bug report, feature requests or any discussion💡.
Thanks to all our contributors who have helped make this project better!
quic-zhanlin |
dingtian777 |
jiaxshi |
quic-zhaoyuan |
Why is RGB image format not supported?
NV12 format is the original format from the Qualcomm camera framework. If you need RGB images, you can use a color conversion node.
Does it support USB cameras?
No, it only supports MIPI-CSI and GMSL cameras, which are based on CamX.
Project is licensed under the BSD-3-Clause License. See LICENSE for the full license text.