Wiki

  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 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)

Published Topics

~cloud_out (sensor_msgs/PointCloud2)

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)

Published Topics

~scan_out (sensor_msgs/LaserScan)

Parameters

~angle_min (float, default: -pi/2) ~angle_max (float, default: +pi/2) ~angle_increment (float, default: 0.0175 (1 degree)) ~time_increment (float, default: 0.0) ~scan_time (float, default: 0.1) ~range_min (float, default: 0.0) ~range_max (float, default: 100.0)

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_vel (geometry_msgs/Twist)

Published Topics

~radar_out (ainstein_radar_msgs/RadarTargetArray)

Parameters

~min_speed_thresh (float, default: 1.0) ~max_speed_thresh (float, default: 1.0) ~compute_3d (bool, default: false) ~is_rotated (bool, default: false)

Required tf Transforms

<the frame attached to incoming data>map

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)

Published Topics

~radar_out (ainstein_radar_msgs/RadarTargetArray)

Parameters

~min_range (float, default: 0.5) ~max_range (float, default: 10.0)

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)

Published Topics

~nearest_target (ainstein_radar_msgs/RadarTargetStamped) ~nearest_target_array (ainstein_radar_msgs/RadarTargetArray)

Parameters

~data_lpf_alpha (float, default: 0.1) ~data_lpf_timeout (float, default: 3.0)

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)

Published Topics

~tracked (ainstein_radar_msgs/RadarTargetArray) ~boxes (jsk_recognition_msgs/BoundingBoxArray)

Parameters

~filter_update_rate (int, default: 20) ~filter_min_time (float, default: 0.5) ~filter_timeout (float, default: 0.5) ~filter_val_gate_thresh (string map, default: 90.0% confidence)

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