diff --git a/perception/autoware_radar_object_clustering/README.md b/perception/autoware_radar_object_clustering/README.md index cf52c33eba274..a5a5c4ee68e5a 100644 --- a/perception/autoware_radar_object_clustering/README.md +++ b/perception/autoware_radar_object_clustering/README.md @@ -65,61 +65,4 @@ So `is_fixed_size` parameter is recommended to set `true`, and size parameters i ### Parameter -- `angle_threshold` (double) [rad] - - Default parameter is 0.174. -- `distance_threshold` (double) [m] - - Default parameter is 4.0. -- `velocity_threshold` (double) [m/s] - - Default parameter is 2.0. - -These parameter are thresholds for angle, distance, and velocity to judge whether radar detections come from one object in "clustering" processing, which is written in detail at algorithm section. -If all of the difference in angle/distance/velocity from two objects is less than the thresholds, then the two objects are merged to one clustered object. -If these parameter is larger, more objects are merged to one clustered object. - -These are used in `isSameObject` function as below. - -```cpp - -bool RadarObjectClusteringNode::isSameObject( - const DetectedObject & object_1, const DetectedObject & object_2) -{ - const double angle_diff = std::abs(autoware::universe_utils::normalizeRadian( - tf2::getYaw(object_1.kinematics.pose_with_covariance.pose.orientation) - - tf2::getYaw(object_2.kinematics.pose_with_covariance.pose.orientation))); - const double velocity_diff = std::abs( - object_1.kinematics.twist_with_covariance.twist.linear.x - - object_2.kinematics.twist_with_covariance.twist.linear.x); - const double distance = autoware::universe_utils::calcDistance2d( - object_1.kinematics.pose_with_covariance.pose.position, - object_2.kinematics.pose_with_covariance.pose.position); - - if ( - distance < node_param_.distance_threshold && angle_diff < node_param_.angle_threshold && - velocity_diff < node_param_.velocity_threshold) { - return true; - } else { - return false; - } -} -``` - -- `is_fixed_label` (bool) - - Default parameter is false. -- `fixed_label` (string) - - Default parameter is "UNKNOWN". - -`is_fixed_label` is the flag to use fixed label. -If it is true, the label of a clustered object is overwritten by the label set by `fixed_label` parameter. -If the radar objects do not have label information, then it is recommended to use fixed label. - -- `is_fixed_size` (bool) - - Default parameter is false. -- `size_x` (double) [m] - - Default parameter is 4.0. -- `size_y` (double) [m] - - Default parameter is 1.5. -- `size_z` (double) [m] - - Default parameter is 1.5. - -`is_fixed_size` is the flag to use fixed size parameters. -If it is true, the size of a clustered object is overwritten by the label set by `size_x`, `size_y`, and `size_z` parameters. +{{ json_to_markdown("perception/autoware_radar_object_clustering/config/radar_object_clustering.param.yaml/schema/radar_object_clustering.schema.json") }} diff --git a/perception/autoware_radar_object_clustering/config/radar_object_clustering.param.yaml b/perception/autoware_radar_object_clustering/config/radar_object_clustering.param.yaml index 2abbf14622a3f..a7b2392f89ba5 100644 --- a/perception/autoware_radar_object_clustering/config/radar_object_clustering.param.yaml +++ b/perception/autoware_radar_object_clustering/config/radar_object_clustering.param.yaml @@ -2,14 +2,14 @@ ros__parameters: # clustering parameter angle_threshold: 0.174 # [rad] (10 deg) - distance_threshold: 10.0 # [m] - velocity_threshold: 4.0 # [m/s] + distance_threshold: 4.0 # [m] + velocity_threshold: 2.0 # [m/s] # output object settings # set false if you want to use the object information from radar - is_fixed_label: true - fixed_label: "CAR" - is_fixed_size: true + is_fixed_label: false + fixed_label: "UNKNOWN" + is_fixed_size: false size_x: 4.0 # [m] size_y: 1.5 # [m] size_z: 1.5 # [m] diff --git a/perception/autoware_radar_object_clustering/schema/radar_object_clustering.schema.json b/perception/autoware_radar_object_clustering/schema/radar_object_clustering.schema.json new file mode 100644 index 0000000000000..e4b6cb2bacb60 --- /dev/null +++ b/perception/autoware_radar_object_clustering/schema/radar_object_clustering.schema.json @@ -0,0 +1,83 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Radar Object Clustering Parameters", + "type": "object", + "definitions": { + "radar_object_clustering": { + "type": "object", + "properties": { + "angle_threshold": { + "type": "number", + "description": "Threshold for angle to determine whether radar detections come from one object during clustering. Larger values merge more objects.", + "default": 0.174 + }, + "distance_threshold": { + "type": "number", + "description": "Threshold for distance to determine whether radar detections come from one object during clustering. Larger values merge more objects.", + "default": 4.0 + }, + "velocity_threshold": { + "type": "number", + "description": "Threshold for velocity to determine whether radar detections come from one object during clustering. Larger values merge more objects.", + "default": 2.0 + }, + "is_fixed_label": { + "type": "boolean", + "description": "Flag to use a fixed label. If true, the label of a clustered object is overwritten by the `fixed_label` parameter.", + "default": false + }, + "fixed_label": { + "type": "string", + "description": "The fixed label to use when `is_fixed_label` is true.", + "default": "UNKNOWN" + }, + "is_fixed_size": { + "type": "boolean", + "description": "Flag to use fixed size parameters. If true, the size of a clustered object is overwritten by the `size_x`, `size_y`, and `size_z` parameters.", + "default": false + }, + "size_x": { + "type": "number", + "description": "Size of the clustered object in the x-dimension, used if `is_fixed_size` is true.", + "default": 4.0 + }, + "size_y": { + "type": "number", + "description": "Size of the clustered object in the y-dimension, used if `is_fixed_size` is true.", + "default": 1.5 + }, + "size_z": { + "type": "number", + "description": "Size of the clustered object in the z-dimension, used if `is_fixed_size` is true.", + "default": 1.5 + } + }, + "required": [ + "angle_threshold", + "distance_threshold", + "velocity_threshold", + "is_fixed_label", + "fixed_label", + "is_fixed_size", + "size_x", + "size_y", + "size_z" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/radar_object_clustering" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +}