Hello ROS Community,
I am Akashleena, an intern at Intrinsic working with @katherine_scott. This summer I am writing a ROS whitepaper that informs sensor vendors on the best practices for developing a ROS 2 package. We want to better understand all of the aspects of writing a good sensor SDK and ROS 2 package. Our goal is to help sensor vendors design their SDK and ROS 2 package such that it is performant, easy to use, and readily available as part of a ROS distro.
We’ve got a few questions that we would like to pose to the ROS community, but first we wanted to share some of our recent work. As part of this project we analyzed many of the sensor packages that are available ROS for Humble. Since searching ROS Index still isn’t great, we’ve compiled a list of all the sensor packages available as binaries for ROS Humble using ROS Distro. Our hope is that you can use this list as a starting point for selecting sensor. To give you an idea about how we’re thinking this problem we also included a table that shows some of the criteria that we used to evaluate a couple sensor packages.
Table: Comparison of ROS Sensor Packages
Metrics | Orbecc drivers | ros2_avt_cameras | lucid_vision_driver | issac_ros_argus_camera | sick_safevisionary_ros2 |
---|---|---|---|---|---|
ROS 2 LTS Support | ☒ | ![]() |
☒ | ☒ | ![]() |
ROS 2 Rolling Support | ☒ | Not sure | ☒ | ☒ | ![]() |
REP-144 Support | Not sure | ![]() |
![]() |
Not Sure | ![]() |
Vendoring the package (is SDK system package?) | ☒ | ![]() |
☒ | ![]() |
![]() |
if SDK not a system package check for .so and .dll | ![]() |
☒ | ☒ | ![]() |
☒ |
Supports cross-linux distribution (support tiers) | Not sure | Not sure | ☒ | Not sure | Not sure |
Uses Standard Messages | ![]() |
covers a lot of proprietary messages which can be replaced with ROS std_msgs | can’t find in repo | ![]() |
![]() |
Includes README, buid script, and sample code. | ![]() |
![]() |
![]() |
![]() |
![]() |
Provides API Docs | ![]() |
![]() |
can be improved ☒ | good docs ![]() |
☒couldn’t find |
Includes Tests (unit, integration, system) | ![]() |
![]() |
☒ | ![]() |
![]() |
Includes ROSBag for quick testing | ☒ | ☒ | ☒ | ![]() |
☒ |
Includes Launch Files | ![]() |
![]() |
![]() |
![]() |
![]() |
QoS Support | ![]() |
![]() |
![]() |
![]() |
![]() |
Composable Nodes | ![]() |
![]() |
![]() |
![]() |
![]() |
Gazebo Plugin / Model | ☒ no sensor model | ☒ no sensor model | ☒ no sensor model | ☒ no sensor model | ☒ no sensor model |
FOSS License | ![]() |
![]() |
![]() |
![]() |
![]() |
Tags Release Artefacts | ![]() |
![]() |
☒ | ![]() |
![]() |
Is the repo well mantained | ![]() |
Not many issues, can’t judge | Not many issues, can’t judge | ![]() |
Not many issues, can’t judge |
Sensor calibration guide? | ![]() |
![]() |
☒ | ![]() |
☒ |
Sensor Diagnostics and Monitoring guide? | can be improved by using diagnostics_msgs | README has diagnostic guide, but can be improved | README has some diganostics guide but needs improvement | ☒needs work | has good lifecycle documentation but can do better in diagnostics |
Sensor Packages Available ROS 2 Humble
For your reference, here’s a list of ROS 2 drivers that we currently available as binary packages in Humble. Please note that this table was procedurally generated, if the package.xml
did not include a description then no description is listed below. We’re providing this list as an easy reference for hardware packages that can be quicky and easily installed using binary ROS packages.
List of Sensor Packages
Depth Cameras
depthai-core
- Description: DepthAI core is a C++ library which comes with firmware and an API to interact with OAK Platform
- Release URL: https://github.com/luxonis/depthai-core-release.git
- Source URL: https://github.com/luxonis/depthai-core.git
nerian_stereo_ros2
- Description: Driver node for ROS 2 for Scarlet, SceneScan and SP1 stereo vision sensors by Nerian Vision GmbH
- Release URL: https://github.com/nerian-vision/nerian_stereo_ros2-release.git
- Source URL: https://github.com/nerian-vision/nerian_stereo_ros2.git
openni2_camera
- Description: nan
- Release URL: https://github.com/ros2-gbp/openni2_camera-release.git
- Source URL: https://github.com/ros-drivers/openni2_camera.git
sick_safevisionary_ros2
- Description: nan
- Release URL: https://github.com/ros2-gbp/sick_safevisionary_ros2-release.git
- Source URL: https://github.com/SICKAG/sick_safevisionary_ros2.git
Conventional Camera Packages
camera_ros
- Description: node for libcamera supported cameras (V4L2, Raspberry Pi Camera Modules)
- Release URL: https://github.com/ros2-gbp/camera_ros-release.git
- Source URL: https://github.com/christianrauch/camera_ros.git
gscam
- Description: A ROS camera driver that uses gstreamer to connect to
devices such as webcams. - Release URL: https://github.com/ros2-gbp/gscam-release.git
- Source URL: https://github.com/ros-drivers/gscam.git
rc_genicam_api
-
Description: GenICam/GigE Vision Convenience Layer.
This package combines the Roboception convenience layer for images with the
GenICam reference implementation and a GigE Vision transport layer. It is a
self contained package that permits configuration and image streaming of
GenICam / GigE Vision 2.0 compatible cameras like the Roboception rc_visard.This package also provides some tools that can be called from the command line
for discovering cameras, changing their configuration and streaming images.
Although the tools are meant to be useful when working in a shell or in a
script, their main purpose is to serve as example on how to use the API for
reading and setting parameters, streaming and synchronizing images.See LICENSE.md for licensing terms of the different parts.
-
Release URL: https://github.com/ros2-gbp/rc_genicam_api-release.git
-
Source URL: https://github.com/roboception/rc_genicam_api.git
usb_cam
- Description: A ROS Driver for V4L USB Cameras
- Release URL: https://github.com/ros2-gbp/usb_cam-release.git
- Source URL: https://github.com/ros-drivers/usb_cam.git
ros2_v4l2_camera
- Description: A ROS 2 camera driver using Video4Linux2
- Release URL: https://github.com/ros2-gbp/ros2_v4l2_camera-release.git
- Source URL: https://gitlab.com/boldhearts/ros2_v4l2_camera.git
avt_vimba_camera
- Description: nan
- Release URL: https://github.com/ros2-gbp/avt_vimba_camera-release.git
- Source URL: https://github.com/astuff/avt_vimba_camera.git
openeb_vendor
- Description: Wrapper around openeb
- Release URL: https://github.com/ros2-gbp/openeb_vendor-release.git
- Source URL: https://github.com/ros-event-camera/openeb_vendor.git
rc_genicam_driver_ros2
- Description: Driver for rc_visard and rc_cube from Roboception GmbH
- Release URL: https://github.com/ros2-gbp/rc_genicam_driver_ros2-release.git
- Source URL: https://github.com/roboception/rc_genicam_driver_ros2.git
stcamera_ros2
- Description: nan
- Release URL: nan
- Source URL: https://github.com/ose-support-ros/stcamera_ros2.git
vimbax_ros2_driver
- Description: nan
- Release URL: https://github.com/ros2-gbp/vimbax_ros2_driver-release.git
- Source URL: https://github.com/alliedvision/vimbax_ros2_driver.git
Non-Conventional cameras
mocap4r2
- Description: nan
- Release URL: https://github.com/MOCAP4ROS2-Project/mocap4r2-release.git
- Source URL: https://github.com/MOCAP4ROS2-Project/mocap4r2.git
flir_camera_driver
- Description: nan
- Release URL: https://github.com/ros-drivers-gbp/flir_camera_driver-release.git
- Source URL: https://github.com/ros-drivers/flir_camera_driver.git
metavision_driver
- Description: ROS 1 and ROS 2 drivers for metavision based event cameras
- Release URL: https://github.com/ros2-gbp/metavision_driver-release.git
- Source URL: https://github.com/ros-event-camera/metavision_driver.git
libcaer_driver
- Description: ROS 2 driver for event base sensors using libcaer
- Release URL: https://github.com/ros2-gbp/libcaer_driver-release.git
- Source URL: https://github.com/ros-event-camera/libcaer_driver.git
LIDAR
sick_safetyscanners2
- Description: ROS 2 Driver for the SICK safetyscanners
- Release URL: https://github.com/SICKAG/sick_safetyscanners2-release.git
- Source URL: https://github.com/SICKAG/sick_safetyscanners2.git
sick_safetyscanners2
- Description: ROS 2 Driver for the SICK safetyscanners
- Release URL: https://github.com/SICKAG/sick_safetyscanners2-release.git
- Source URL: https://github.com/SICKAG/sick_safetyscanners2.git
sick_safetyscanners2_interfaces
- Description: Interfaces for the sick_safetyscanners ROS 2 driver
- Release URL: https://github.com/SICKAG/sick_safetyscanners2_interfaces-release.git
- Source URL: https://github.com/SICKAG/sick_safetyscanners2_interfaces.git
sick_safetyscanners_base
- Description: Provides an Interface to read the sensor output of a SICKSafety Scanner
- Release URL: https://github.com/SICKAG/sick_safetyscanners_base-release.git
- Source URL: https://github.com/SICKAG/sick_safetyscanners_base.git
sick_scan_xd
- Description: ROS 1 and 2 driver for SICK scanner
- Release URL: https://github.com/ros2-gbp/sick_scan_xd-release.git
- Source URL: https://github.com/SICKAG/sick_scan_xd.git
hls_lfcd_lds_driver
- Description: ROS package for LDS(HLS-LFCD2).
The LDS (Laser Distance Sensor) is a sensor sending the data to Host for the simultaneous localization and mapping (SLAM). Simultaneously the detecting obstacle data can also be sent to Host. HLDS(Hitachi-LG Data Storage) is developing the technology for the moving platform sensor such as Robot Vacuum Cleaners, Home Robot, Robotics Lawn Mower Sensor, etc. - Release URL: https://github.com/ros2-gbp/hls_lfcd_lds_driver-release.git
- Source URL: https://github.com/ROBOTIS-GIT/hls_lfcd_lds_driver.git
LMS1xx
- Description: The lms1xx package contains a basic ROS 2 driver for the SICK LMS1xx line of LIDARs.
- Release URL: https://github.com/clearpath-gbp/LMS1xx-release.git
- Source URL: https://github.com/clearpathrobotics/LMS1xx.git
rplidar_ros
- Description: The rplidar ros package, support rplidar A1/A2/A3/S1/S2/S3/T1
- Release URL: https://github.com/ros2-gbp/rplidar_ros-release.git
- Source URL: https://github.com/Slamtec/rplidar_ros.git
lsc_ros2_driver
- Description: ROS 2 driver package for Autonics LSC Series
- Release URL: https://github.com/AutonicsLiDAR-release/lsc_ros2_driver-release.git
- Source URL: https://github.com/AutonicsLiDAR/lsc_ros2_driver.git
ros2_ouster_drivers
- Description: nan
- Release URL: https://github.com/ros2-gbp/ros2_ouster_drivers-release.git
- Source URL: https://github.com/SteveMacenski/ros2_ouster_drivers.git
urg_node
- Description: urg_node
- Release URL: https://github.com/ros2-gbp/urg_node-release.git
- Source URL: https://github.com/ros-drivers/urg_node.git
velodyne
- Description: nan
- Release URL: https://github.com/ros2-gbp/velodyne-release.git
- Source URL: https://github.com/ros-drivers/velodyne.git
List of Other Sensor Drivers
aandd_ekew_driver_py
- Description: aandd ek/ew series driver Python package
- Release URL: https://github.com/ros2-gbp/aandd_ekew_driver_py-release.git
- Source URL: https://github.com/TechMagicKK/aandd_ekew_driver_py.git
bno055
- Description: Bosch BNO055 IMU driver for ROS 2
- Release URL: https://github.com/ros2-gbp/bno055-release.git
- Source URL: https://github.com/flynneva/bno055.git
ess_imu_driver2
- Description: ROS 2 package for Epson IMU based on C++ wrapper of Linux C driver
- Release URL: https://github.com/ros2-gbp/ess_imu_driver2-release.git
- Source URL: https://github.com/cubicleguy/ess_imu_driver2.git
fadecandy_ros
- Description: nan
- Release URL: https://github.com/eurogroep/fadecandy_ros-release.git
- Source URL: https://github.com/eurogroep/fadecandy_ros.git
naoqi_driver2
- Description: Driver module between Aldebaran’s NAOqiOS and ROS 2. It publishes all sensor and actuator data as well as basic diagnostic for battery, temperature. It subscribes also to RVIZ simple goal and cmd_vel for teleop.
- Release URL: https://github.com/ros-naoqi/naoqi_driver2-release.git
- Source URL: https://github.com/ros-naoqi/naoqi_driver2.git
novatel_gps_driver
- Description: nan
- Release URL: https://github.com/ros2-gbp/novatel_gps_driver-release.git
- Source URL: https://github.com/swri-robotics/novatel_gps_driver.git
novatel_oem7_driver
- Description: nan
- Release URL: https://github.com/novatel-gbp/novatel_oem7_driver-release.git
- Source URL: https://github.com/novatel/novatel_oem7_driver.git
off_highway_sensor_drivers
- Description: nan
- Release URL: https://github.com/ros2-gbp/off_highway_sensor_drivers-release.git
- Source URL: https://github.com/bosch-engineering/off_highway_sensor_drivers.git
phidgets_drivers
- Description: nan
- Release URL: https://github.com/ros2-gbp/phidgets_drivers-release.git
- Source URL: https://github.com/ros-drivers/phidgets_drivers.git
rt_usb_9axisimu_driver
- Description: The rt_usb_9axisimu_driver package
- Release URL: https://github.com/ros2-gbp/rt_usb_9axisimu_driver-release.git
- Source URL: https://github.com/rt-net/rt_usb_9axisimu_driver.git
septentrio_gnss_driver
- Description: ROSaic: C++ driver for Septentrio’s GNSS and INS receivers
- Release URL: https://github.com/ros2-gbp/septentrio_gnss_driver_ros2-release.git
- Source URL: https://github.com/septentrio-gnss/septentrio_gnss_driver.git
ublox
- Description: nan
- Release URL: https://github.com/ros2-gbp/ublox-release.git
- Source URL: https://github.com/KumarRobotics/ublox.git
ublox_dgnss
- Description: nan
- Release URL: https://github.com/ros2-gbp/ublox_dgnss-release.git
- Source URL: https://github.com/aussierobots/ublox_dgnss.git
What do you think makes a good sensor package?
We would love to hear from the community what makes a great sensor package! We’ve come up with a list of questions and we would love it if the ROS community provided their feedback on these topics:
- What do you look for in the architecture of a ROS package for a sensor? What makes for a “well-written” sensor package?
- Sensor calibration and cross-callibration is still a bit of a “black-art” in ROS. What tools are using for sensor calibration? What features would you like to see in sensor packages to improve calibration and cross calibration?"
- One thing we’ve noticed is that Gazebo support for sensors is often missing. Most sensors lack URDF or STL files that define sensor’s hardware geometry. Moreover, most vendors don’t provide a Gazebo sensor plugin. What steps do you take to to integrate simulated sensors into your robot model in Gazebo? What would you like to see sensor vendors provide?
- How important is it for sensor vendors to provide support for Tier 2 and Tier 3 supported operating systems? Is anyone out there building robots on top of operating systems like RHEL and Debian? If you are using these host operating systems what would you like to see?
- Are there any specific things you would like to sensor vendors provide in their documentation or tests? Are there any sensor packages that you particularly like?
- ROS 1 supported nodelets which were included in launch file of the sensors and allowed multiple nodes to share the same process. How are you performing similar interprocess communication in ROS 2? What would your recommendations be for similar features in ROS 2?
- In ROS 1, the
SubscriberStatusCallback
was a key element in image pipeline to coordinate the sequence of nodes from layering to rectification. ROS 2 lacks this callback requiring frequent checks to find active subscribers. How are you achieving similar results in ROS 2? - How are you using lifecycle nodes in ROS 2 to monitor the sensor states?