Skip to content

autoware_radar_objects_adapter#

Purpose#

This package converts autoware_sensing_msgs::msg::RadarObjects into autoware_perception_msgs::msg::DetectedObjects, acting as a simple integration of radars into the perception pipeline.

RadarObjectsAdapter#

A node that converts radar objects from the sensing definition into a perception friendly format with no filtering involved.

Parameter: classification_remap#

This parameter allows remapping of classification labels from autoware_sensing_msgs::msg::RadarClassification to autoware_perception_msgs::msg::ObjectClassification. It should be provided as a flat list of strings, where each pair of strings represents an input label and the corresponding output label.

For example, the current default configuration remaps MOTORCYCLE and BICYCLE from radar classification to CAR in the perception classification, while keeping other labels unchanged.

Note: If multiple radar labels are remapped to the same perception label, multiple probabilities may appear for that label. This does not violate any logic in Autoware but may be worth monitoring.

Inputs / Outputs#

Input#

Name Type Description
~/input/objects autoware_sensing_msgs::msg::RadarObjects Input radar objects as defined in sensing.
~/input/radar_info autoware_sensing_msgs::msg::RadarInfo Input radar info.

Output#

Name Type Description
~/output/objects autoware_perception_msgs::msg::DetectedObjects Output radar objects in the perception format.

Parameters#

Name Type Description Default Range
default_position_z float The default z-coordinate in meters of the position of radar objects in the case the radar does not provide it. 0.0 N/A
default_velocity_z float The default z-coordinate in meters per second of the velocity of radar objects in the case the radar does not provide it. 0.0 N/A
default_acceleration_z float The default z-coordinate in meters per squared second of the acceleration of radar objects in the case the radar does not provide it. 0.0 N/A
default_size_x float The default x-coordinate in meters of the size of radar objects in the case the radar does not provide it. 5.0 N/A
default_size_y float The default y-coordinate in meters of the size of radar objects in the case the radar does not provide it. 2.0 N/A
default_size_z float The default z-coordinate in meters of the size of radar objects in the case the radar does not provide it. 2.0 N/A
classification_remap.UNKNOWN string Radar class to map to UNKNOWN label. UNKNOWN N/A
classification_remap.CAR string Radar class to map to CAR label. CAR N/A
classification_remap.TRUCK string Radar class to map to TRUCK label. TRUCK N/A
classification_remap.MOTORCYCLE string Radar tends to misclassify far cars as MOTORCYCLE; default=CAR CAR N/A
classification_remap.BICYCLE string Radar tends to misclassify far cars as BICYCLE; default=CAR CAR N/A
classification_remap.PEDESTRIAN string Radar class to map to PEDESTRIAN label. PEDESTRIAN N/A
classification_remap.ANIMAL string Radar class to map to ANIMAL label. ANIMAL N/A
classification_remap.HAZARD string HAZARD is not a valid Perception label; fallback=UNKNOWN UNKNOWN N/A