Show EOL distros: 

Package Summary

Filtering and data conversion utilities for radar data.

  • Maintainer status: maintained
  • Maintainer: Nick Rotella <nick.rotella AT ainstein DOT ai>
  • Author: Nick Rotella
  • License: BSD

Package Summary

Filtering and data conversion utilities for radar data.

  • Maintainer status: maintained
  • Maintainer: Nick Rotella <nick.rotella AT ainstein DOT ai>
  • Author: Nick Rotella
  • License: BSD

Overview

This package is intended to contain a variety of data conversion and filtering utilities. Currently supported are the following:

  • Conversion from radar data to pointcloud data, for use with eg. open-source point cloud library PCL
  • Conversion from radar data to laserscan data, for use with eg. open-source SLAM package gmapping
  • Filtering of radar data based on range
  • Filtering of radar data based on relative speed in radar frame
  • Filtering of radar data to nearest target
  • Tracking of radar targets based on raw detections

Conversion Nodes

radar_target_array_to_point_cloud_node

Subscribes to radar data, converts to custom radar pointcloud data and publishes as a standard pointcloud message.

Subscribed Topics

~radar_in (ainstein_radar_msgs/RadarTargetArray)
  • Radar detections (targets) to be converted to pointcloud data.

Published Topics

~cloud_out (sensor_msgs/PointCloud2)
  • Published pointcloud data corresponding to input radar data.

radar_target_array_to_laser_scan_node

Subscribes to radar data, converts to and publishes as a standard laserscan message.

Subscribed Topics

~radar_in (ainstein_radar_msgs/RadarTargetArray)
  • Radar detections (targets) to be converted to pointcloud data.

Published Topics

~scan_out (sensor_msgs/LaserScan)
  • Published laserscan data corresponding to input radar data.

Parameters

~angle_min (float, default: -pi/2)
  • Minimum angle represented in the laserscan, in radians.
~angle_max (float, default: +pi/2)
  • Maximum angle represented in the laserscan, in radians.
~angle_increment (float, default: 0.0175 (1 degree))
  • Angle increment per laserscan beam, in radians.
~time_increment (float, default: 0.0)
  • Time increment per laserscan sample, in seconds.
~scan_time (float, default: 0.1)
  • Time increment per scan, in seconds.
~range_min (float, default: 0.0)
  • Minimum range of the laserscan, in meters.
~range_max (float, default: 100.0)
  • Maximum range of the laserscan, in meters.

Filter Nodes

radar_target_array_speed_filter_node and radar_target_array_speed_filter_nodelet

Filters radar targets based on relative speed along the radar measurement direction, assuming radar world-frame velocity is published by another node (eg from GPS). Can filter either by min or max speed (to preserve only stationary or moving targets, respectively); if either min/max speed threshold is not set as a parameter, it is not used for filtering. Also contains untested functionality for using the radar in a rotated fashion for obtaining 3d data.

Subscribed Topics

~radar_in (ainstein_radar_msgs/RadarTargetArray)
  • Radar detections (targets) to be converted to pointcloud data.
radar_vel (geometry_msgs/Twist)
  • Speed of the radar assumed to be in world (map) frame. Only the linear portion is used. If this topic is not available, no speed filtering is performed and the output radar data is identical to the input.

Published Topics

~radar_out (ainstein_radar_msgs/RadarTargetArray)
  • Speed-filtered radar detections (targets).

Parameters

~min_speed_thresh (float, default: 1.0)
  • Minimum speed of output radar targets, in meters per second.
~max_speed_thresh (float, default: 1.0)
  • Maximum speed of output radar targets, in meters per second.
~compute_3d (bool, default: false)
  • Specifies whether to use the 2d radar to compute 3d data (UNTESTED).
~is_rotated (bool, default: false)
  • If compute_3d is true, then this specifies whether to use speed information to compute elevation if rotated or azimuth if not rotated (UNTESTED).

Required tf Transforms

<the frame attached to incoming data>map
  • Transformation from the radar data frame to the map (world) frame.

radardata_range filter_node and radardata_range filter_nodelet

Filters radar targets based on reported range, with dynamically-reconfigurable limits.

Subscribed Topics

~radar_in (ainstein_radar_msgs/RadarTargetArray)
  • Radar detections (targets) to be filtered.

Published Topics

~radar_out (ainstein_radar_msgs/RadarTargetArray)
  • Range-filtered radar detections (targets).

Parameters

~min_range (float, default: 0.5)
  • Minimum range of output radar targets, in meters (DYNAMICALLY-RECONFIGURABLE).
~max_range (float, default: 10.0)
  • Maximum range of output radar targets, in meters (DYNAMICALLY-RECONFIGURABLE).

radardata_to_nearest_target_node

Filters radar targets down to the nearest target, published both as a single stamped target and in an array with a single target entry (for compatibility with other nodes). Also performs range filtering and optionally low-pass filters the nearest target data to help smooth the fact that it may jump around considerably (a simple form of target tracking).

Subscribed Topics

~radar_in (ainstein_radar_msgs/RadarTargetArray)
  • Radar detections (targets) to be filtered.

Published Topics

~nearest_target (ainstein_radar_msgs/RadarTargetStamped)
  • Nearest radar detection, timestamped.
~nearest_target_array (ainstein_radar_msgs/RadarTargetArray)
  • Nearest radar detection as the single entry in a target array.

Parameters

~data_lpf_alpha (float, default: 0.1)
  • Low-pass filter constant (0-1).
~data_lpf_timeout (float, default: 3.0)
  • Timeout after which the "tracked" (filtered) target is re-initialized, in seconds.

radardata_to_tracked_targets_node

Filters raw radar targets into tracked targets by instantiating Kalman Filters for each tracked target, running a simple kinematic process model and updating each with raw targets based on a measurement error check (validation gating). If a raw target does not correspond to an existing tracked target, it is added with a new KF and published after a specified time alive. Conversely, if a tracked target is not updated for a specified period of time, it is dropped from the filter. Additional parameters for the underlying KF implementation exist but are not listed below, see here and tutorials for details. These generally need not be changed.

Subscribed Topics

~radar_in (ainstein_radar_msgs/RadarTargetArray)
  • Radar detections (targets) to be used for outputting tracked targets.

Published Topics

~tracked (ainstein_radar_msgs/RadarTargetArray)
  • Tracked targets output after updating Kalman Filters.
~boxes (jsk_recognition_msgs/BoundingBoxArray)
  • Bounding boxes corresponding to each tracked target, formed from all raw detections associated with that tracked target after the current update.

Parameters

~filter_update_rate (int, default: 20)
  • Rate at which the filter is run, in Hz.
~filter_min_time (float, default: 0.5)
  • Minimum time a target must be tracked before being published, in seconds (DYNAMICALLY-RECONFIGURABLE).
~filter_timeout (float, default: 0.5)
  • Maximum time a tracked target can not be updated before being dropped, in seconds (DYNAMICALLY-RECONFIGURABLE).
~filter_val_gate_thresh (string map, default: 90.0% confidence)
  • Validation gate confidence threshold map - see here for options (DYNAMICALLY-RECONFIGURABLE).

Wiki: ainstein_radar_filters (last edited 2019-11-13 22:38:18 by AinsteinAi)