From dcde1b94a0f1565f0c520f95469c008261677bcb Mon Sep 17 00:00:00 2001 From: Boyang Date: Thu, 6 Jun 2024 13:26:09 -0400 Subject: [PATCH] Deleted the default values in the source code, updated .param.yaml files, created schema.json files, updated readme. --- perception/lidar_centerpoint_tvm/README.md | 8 +- .../config/centerpoint.param.yaml | 9 ++ .../schema/centerpoint.schema.json | 129 ++++++++++++++++++ perception/lidar_centerpoint_tvm/src/node.cpp | 15 +- .../src/single_inference_node.cpp | 14 +- 5 files changed, 156 insertions(+), 19 deletions(-) create mode 100644 perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json diff --git a/perception/lidar_centerpoint_tvm/README.md b/perception/lidar_centerpoint_tvm/README.md index 26d588d4483ad..4ebddf275b71d 100644 --- a/perception/lidar_centerpoint_tvm/README.md +++ b/perception/lidar_centerpoint_tvm/README.md @@ -36,13 +36,7 @@ It defaults to `llvm`. ## Parameters -### Core Parameters - -| Name | Type | Default Value | Description | -| ------------------------------- | ------ | ------------- | ----------------------------------------------------------- | -| `score_threshold` | float | `0.1` | detected objects with score less than threshold are ignored | -| `densification_world_frame_id` | string | `map` | the world frame id to fuse multi-frame pointcloud | -| `densification_num_past_frames` | int | `1` | the number of past frames to fuse with the current frame | +{{ json_to_markdown("perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json") }} ### Bounding Box diff --git a/perception/lidar_centerpoint_tvm/config/centerpoint.param.yaml b/perception/lidar_centerpoint_tvm/config/centerpoint.param.yaml index 34dce71975985..68eb68bd3a296 100644 --- a/perception/lidar_centerpoint_tvm/config/centerpoint.param.yaml +++ b/perception/lidar_centerpoint_tvm/config/centerpoint.param.yaml @@ -8,3 +8,12 @@ voxel_size: [0.32, 0.32, 8.0] downsample_factor: 1 encoder_in_feature_size: 9 + has_twist: false + post_process_params: + # post-process params + circle_nms_dist_threshold: 1.5 + score_threshold: 0.35 + yaw_norm_threshold: 0.0 + densification_params: + world_frame_id: map + num_past_frames: 1 diff --git a/perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json b/perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json new file mode 100644 index 0000000000000..d4f9f2f3a8092 --- /dev/null +++ b/perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json @@ -0,0 +1,129 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Lidar Centerpoint TVM Node", + "type": "object", + "definitions": { + "centerpoint": { + "type": "object", + "properties": { + "class_names": { + "type": "array", + "description": "List of class names for object detection.", + "items": { + "type": "string" + }, + "default": ["CAR", "PEDESTRIAN", "BICYCLE"] + }, + "rename_car_to_truck_and_bus": { + "type": "boolean", + "description": "Flag to rename car detections to truck and bus.", + "default": true + }, + "point_feature_size": { + "type": "integer", + "description": "The size of the point features.", + "default": 4 + }, + "max_voxel_size": { + "type": "integer", + "description": "The maximum number of voxels.", + "default": 40000 + }, + "point_cloud_range": { + "type": "array", + "description": "The range of the point cloud.", + "items": { + "type": "number" + }, + "default": [-89.6, -89.6, -3.0, 89.6, 89.6, 5.0] + }, + "voxel_size": { + "type": "array", + "description": "The size of the voxels.", + "items": { + "type": "number" + }, + "default": [0.32, 0.32, 8.0] + }, + "downsample_factor": { + "type": "integer", + "description": "The factor by which to downsample the point cloud.", + "default": 1 + }, + "encoder_in_feature_size": { + "type": "integer", + "description": "The size of the input features for the encoder.", + "default": 9 + }, + "has_twist": { + "type": "boolean", + "description": "Flag to indicate if the twist (velocity) is included.", + "default": false + }, + "post_process_params": { + "type": "object", + "properties": { + "circle_nms_dist_threshold": { + "type": "number", + "description": "The distance threshold for circle NMS.", + "default": 1.5 + }, + "score_threshold": { + "type": "number", + "description": "Detected objects with score less than threshold are ignored.", + "default": 0.35 + }, + "yaw_norm_threshold": { + "type": "number", + "description": "The threshold for yaw normalization.", + "default": 0.0 + } + }, + "required": ["circle_nms_dist_threshold", "score_threshold", "yaw_norm_threshold"] + }, + "densification_params": { + "type": "object", + "properties": { + "world_frame_id": { + "type": "string", + "description": "The world frame id to fuse multi-frame pointcloud.", + "default": "map" + }, + "num_past_frames": { + "type": "integer", + "description": "The number of past frames to fuse with the current frame.", + "default": 1 + } + }, + "required": ["world_frame_id", "num_past_frames"] + } + }, + "required": [ + "class_names", + "rename_car_to_truck_and_bus", + "point_feature_size", + "max_voxel_size", + "point_cloud_range", + "voxel_size", + "downsample_factor", + "encoder_in_feature_size", + "has_twist", + "post_process_params", + "densification_params" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/centerpoint" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] + } + \ No newline at end of file diff --git a/perception/lidar_centerpoint_tvm/src/node.cpp b/perception/lidar_centerpoint_tvm/src/node.cpp index 288b8d59aec21..d847274b8c0d3 100644 --- a/perception/lidar_centerpoint_tvm/src/node.cpp +++ b/perception/lidar_centerpoint_tvm/src/node.cpp @@ -41,15 +41,20 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod : Node("lidar_centerpoint_tvm", node_options), tf_buffer_(this->get_clock()) { const float score_threshold = - static_cast(this->declare_parameter("score_threshold", 0.35)); + static_cast(this->declare_parameter("post_process_params.score_threshold")); const float circle_nms_dist_threshold = - static_cast(this->declare_parameter("circle_nms_dist_threshold", 1.5)); + static_cast(this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const float yaw_norm_threshold = - static_cast(this->declare_parameter("yaw_norm_threshold", 0.0)); + static_cast(this->declare_parameter("post_process_params.yaw_norm_threshold")); const std::string densification_world_frame_id = - this->declare_parameter("densification_world_frame_id", "map"); + this->declare_parameter("densification_params.world_frame_id"); const int32_t densification_num_past_frames = - this->declare_parameter("densification_num_past_frames", 1); + this->declare_parameter("densification_params.num_past_frames"); + + class_names_ = this->declare_parameter>("class_names"); + rename_car_to_truck_and_bus_ = this->declare_parameter("rename_car_to_truck_and_bus"); + has_twist_ = this->declare_parameter("has_twist"); + class_names_ = this->declare_parameter>("class_names"); rename_car_to_truck_and_bus_ = this->declare_parameter("rename_car_to_truck_and_bus", false); diff --git a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp index 224664e51ea2d..bfe4ef607bfa6 100644 --- a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp +++ b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp @@ -46,18 +46,18 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode( : Node("lidar_center_point_tvm", node_options), tf_buffer_(this->get_clock()) { const float score_threshold = - static_cast(this->declare_parameter("score_threshold", 0.35)); + static_cast(this->declare_parameter("post_process_params.score_threshold")); const float circle_nms_dist_threshold = - static_cast(this->declare_parameter("circle_nms_dist_threshold", 1.5)); + static_cast(this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const float yaw_norm_threshold = - static_cast(this->declare_parameter("yaw_norm_threshold", 0.0)); + static_cast(this->declare_parameter("post_process_params.yaw_norm_threshold")); const std::string densification_world_frame_id = - this->declare_parameter("densification_world_frame_id", "map"); - const int densification_num_past_frames = - this->declare_parameter("densification_num_past_frames", 0); + this->declare_parameter("densification_params.world_frame_id"); + const int32_t densification_num_past_frames = + this->declare_parameter("densification_params.num_past_frames"); class_names_ = this->declare_parameter>("class_names"); - has_twist_ = this->declare_parameter("has_twist", false); + has_twist_ = this->declare_parameter("has_twist"); const std::size_t point_feature_size = static_cast(this->declare_parameter("point_feature_size")); const std::size_t max_voxel_size =