(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Converting radar data to PointCloud2 and LaserScan

Description: Guide to converting from custom radar data messages to standard ROS sensor messages

Tutorial Level: BEGINNER

Next Tutorial: Target tracking from raw radar detections

Overview

The ainstein_radar_filters subpackage contains, among other tools, nodes for converting from the custom radar data message types to standard ROS sensor data message types.

The package design philosophy is that a radar sensor should natively output radar-specific messages, however for use in downstream applications it's likely necessary to convert to a standard ROS message. This can be accomplished simply as detailed below.

Note also that visualizing large amounts of data in the native radar message type can cause lag in RViz. In this case, it's suggested to convert to point cloud data and visualize this instead.

K79_3D_cloud.png

Converting ainstein_radar_msgs/RadarTargetArray to sensor_msgs/PointCloud2

Background

The sensor_msgs/PointCloud2 message type is the standard output type from many 3d perception sensors, including LIDAR and stereo cameras. As imaging radar begins to approach the point density of these sensors, it makes sense to convert to this native ROS message type for use with existing perception stacks.

Further, the PointCloud2 type is easily converted back and forth to PCL point clouds, granting access to a great number of open-source point cloud processing algorithms. PCL itself is highly-templated to allow the library to represent arbitrary point cloud types having additional data, for example RGB data for stereo sensors or intensities for LIDAR. This allows us to define a custom PointRadarTarget PCL datatype which stores the original radar data (range, speed, angles and SNR) alongside the Cartesian 3d point. By preserving this information in the converted PointCloud2 message, we gain access to filtering and visualization tools for PointCloud2 message (more on that in future tutorials).

Usage

The radar_target_array_to_point_cloud_node subscribes to a topic radar_in of type RadarTargetArray and publishes a sensor_msgs/PointCloud2 message to topic ~cloud_out (reminder: ~ denotes private scoping).

Example launch file usage (note that the remaps are optional):

   1 <node name="radar_to_cloud" pkg="ainstein_radar_filters" type="radar_target_array_to_point_cloud_node" >
   2     <remap from="radar_in" to="YOUR_INPUT_RADAR_TOPIC" />
   3     <remap from="~cloud_out" to="DESIRED_OUTPUT_CLOUD_TOPIC" />
   4 </node>

Converting ainstein_radar_msgs/RadarTargetArray to sensor_msgs/LaserScan

Background

The sensor_msgs/LaserScan message type is output from many 2d scanners, reporting the range to the nearest object at a fixed angular resolution. While radar does not return range and speed at specified angles, it can still be useful to convert to a LaserScan message for use with other packages (for example, gmapping.

Note that while most radar data is already nearest object in 2d (zero elevation angle), depending on the antenna there may be a small elevation sensitivity which causes multiple returns at roughly the same azimuth angle. In this case, only the nearest return at that azimuth angle is passed through to the LaserScan message. In a similar manner, 3d radar data gets compressed to 2d.

Usage

The radar_target_array_to_laser_scan_node subscribes to a topic radar_in of type RadarTargetArray and publishes a sensor_msgs/LaserScan message to topic scan_out.

Example launch file usage (note that the remaps are optional):

   1 <node name="radar_to_scan" pkg="ainstein_radar_filters" type="radar_targetr_array_to_laser_scan_node" >
   2     <remap from="radar_in" to="YOUR_INPUT_RADAR_TOPIC" />
   3     <remap from="~scan_out" to="DESIRED_OUTPUT_SCAN_TOPIC" />
   4 </node>

Wiki: ainstein_radar/Tutorials/Converting radar data to PointCloud2 and LaserScan (last edited 2019-11-22 15:46:05 by AinsteinAi)