royale-ros is a wrapper around the pmd Royale SDK enabling the usage of pmd-based ToF cameras from within ROS software systems.
royale-ros version | Royale SDK version | Linux/ROS distribution pair(s) | Supported Hardware |
---|---|---|---|
0.1.0 | 3.5 |
Ubuntu 16.04/Kinetic, Ubuntu 14.04/Indigo |
Pico Flexx |
NOTE: Theoretically, any camera supported by Royale will be compatible with this library. However, the above listed hardware is what we have available to us for testing. We welcome your feedback related to other Royale-based cameras and their compatibility with this ROS interface.
NOTE 2: This library is (currently) limited to Royale's Level 1 access features.
Building and installing the software has two primary steps:
The core royale-ros
sensor interface is implemented as a ROS nodelet. This
allows for lower-latency data processing vs. the traditional out-of-process
node-based ROS interface for applications that require it. However, we ship a
launch file with this package that allows for using the core royale-ros
driver as a standard node. To launch the node the following command can be
used:
$ roslaunch royale_ros camera.launch
This launch file encapsulates several features:
- It exposes some of the
camera_nodelet
parameters as command-line arguments for ease of runtime configuration. - It instantiates a nodelet manager which the
camera_nodelet
will be loaded into. - It launches the
camera_nodelet
itself. - It publishes the static transform from the camera's optical frame to a
traditional ROS sensor frame as a tf2
static_transform_publisher
.
You can either use this launch file directly, or, use
it as a basis for integrating royale-ros
into your own robot software
system.
Name | Data Type | Default Value | Description |
---|---|---|---|
~on_at_startup | bool | true | The pmd cameras use an active illumination unit as part of its ToF measurement principle to compute the distance to objects in the scene. Continuously pulsing the illumination unit both consumes power and generates heat. To that end, for some applications, it is desireable to have the ability to turn on/off the illumination unit in software. royale-ros provides that capability through a ROS service call (see below). This parameter controls whether or not the camera will start pulsing its illumination unit (and by extension, streaming image data) at node startup time. |
~serial_number | string | - | Each pmd camera has a unique serial number. Each instance of the royale-ros camera nodelet manages the data from a specific camera instance. This parameter controls which specific camera serial number this instance of the nodelet should manage. The special string "-" (a minus sign, no quotes) communicates to the nodelet that the first camera found on the USB bus should be used. This is convenient for cases where you will only ever be using a single camera but may be using many different cameras with different serial numbers. At the same time, having this serial number mapping allows for robust robot configurations whereby you can map camera serial numbers to semantically meaningful node names (e.g., serial number XXX = front_left_camera). |
~initial_use_case | string | - | pmd-based Royale cameras encapsulate a set of camera and imager settings into the notion of a "use case". These use cases give a name to a set of prepackaged parameter settings. This parameter allows for setting a particular use case on the camera at nodelet startup time. The use case can be changed at any point in time via the Config service, however, this simplifies setting the use case at startup. The special (and default) value of "-" (a minus sign, no quotes) communicates to the nodelet that no particular use case should be set at startup time. |
~poll_bus_secs | float | 1. | Integral to the camera nodelet is a running watchdog timer. This parameter controls the frequency at which the watchdog will run a health check loop. This is also the mechanism by which this nodelet provides robustness to a camera cable being unplugged and re-plugged back in (something that could very likely happen in an industrial setting due to pinched cables, etc.). Every poll_bus_secs this node will try to reinitialize the camera should it become unplugged for whatever reason. |
~timeout_secs | float | 1. | This is a threshold value used by the nodelet to determine that a running camera has timed-out or otherwise become unavailable. On every iteration of the watchdog (i.e., every poll_bus_secs), if the camera is currently "on", a check is made to see if frame data have been received within this timeout threshold. If this timeout threshold has been exceeded, the camera will be reinitialized. |
~optical_frame | string | camera_optical_link | The name of the optical frame in the tf tree |
~sensor_frame | string | camera_link | The name of the sensor frame in the tf tree |
NOTE: pmd cameras can produce data with different imager settings
simulataneously. This is the so-called mixed mode feature. For a particular
use case there will be one or more data streams that it offers. So for each
image topic published by royale-ros
, we namespace it into a stream. While
Royale gives each camera stream a unique stream id encoded as a uint16
,
for the purpose of topic names, royale-ros
streams are simply positive
integers. So, for example, the point cloud topic for a single stream use case
will be published on stream/1/cloud
. For a mixed-mode use case (lets assume
two data streams), the point clouds will be published on stream/1/cloud
and
stream/2/cloud
. In the table below, we use the variable X
as a
placeholder for the stream number.
Name | Data Type | Description |
---|---|---|
stream/X/camera_info | sensor_msgs/CameraInfo | The intrinsic calibration parameters for the camera |
stream/X/cloud | sensor_msgs/PointCloud2 | The point cloud data |
stream/X/conf | sensor_msgs/Image | The pixel confidence image |
stream/X/gray | sensor_msgs/Image | The amplitude image |
stream/X/noise | sensor_msgs/Image | The noise image |
stream/X/xyz | sensor_msgs/Image | The point cloud data (Cartesian data only, no amplitude) encoded as a three channel (the x, y, z spatial planes respectively) OpenCV image. |
stream/X/exposure_times | royale_ros/ExposureTimes | The exposure times used to acquire the pixel data. |
Name | Data Type | Description |
---|---|---|
SetExposureTime | royale_ros/SetExposureTime | Allows for a lightweight/fast means to change the exposure time for the current use case on-the-fly (assuming the camera is in a manual exposure mode). |
Name | Service Definition | Description |
---|---|---|
Dump | royale_ros/Dump | Dumps the state of the camera parameters to JSON |
Config | royale_ros/Config | Provides a means to configure the camera and imager settings, declaratively from a JSON encoding of the desired settings. |
Start | royale_ros/Start | Starts the camera data stream |
Stop | royale_ros/Stop | Stops the camera data stream and, by extension, turns off the active illumination unit. |
- Listing serial numbers of currently connected cameras
- Inspecting and configuring the camera/imager settings
- Changing the exposure time on the fly
- Handling multiple cameras
The current TODO list is located here. Please also see the Github Issues.
Please see the file called LICENSE.
The initial development of royale-ros
has been sponsored by
Locus Robotics. The authors thank them for
their contribution to the open-source robotics community.
Tom Panzarella tom@loveparkrobotics.com