Skip to content

Commit

Permalink
Deleted the default values in the source code, updated .param.yaml fi…
Browse files Browse the repository at this point in the history
…les, created schema.json files, updated readme.
  • Loading branch information
tby-udel committed Jun 6, 2024
1 parent 2022fc9 commit dcde1b9
Show file tree
Hide file tree
Showing 5 changed files with 156 additions and 19 deletions.
8 changes: 1 addition & 7 deletions perception/lidar_centerpoint_tvm/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
129 changes: 129 additions & 0 deletions perception/lidar_centerpoint_tvm/schema/centerpoint.schema.json
Original file line number Diff line number Diff line change
@@ -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": ["/**"]
}

15 changes: 10 additions & 5 deletions perception/lidar_centerpoint_tvm/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<float>(this->declare_parameter<double>("score_threshold", 0.35));
static_cast<float>(this->declare_parameter<double>("post_process_params.score_threshold"));
const float circle_nms_dist_threshold =
static_cast<float>(this->declare_parameter<double>("circle_nms_dist_threshold", 1.5));
static_cast<float>(this->declare_parameter<double>("post_process_params.circle_nms_dist_threshold"));
const float yaw_norm_threshold =
static_cast<float>(this->declare_parameter<double>("yaw_norm_threshold", 0.0));
static_cast<float>(this->declare_parameter<double>("post_process_params.yaw_norm_threshold"));
const std::string densification_world_frame_id =
this->declare_parameter("densification_world_frame_id", "map");
this->declare_parameter<std::string>("densification_params.world_frame_id");
const int32_t densification_num_past_frames =
this->declare_parameter("densification_num_past_frames", 1);
this->declare_parameter<int>("densification_params.num_past_frames");

class_names_ = this->declare_parameter<std::vector<std::string>>("class_names");
rename_car_to_truck_and_bus_ = this->declare_parameter<bool>("rename_car_to_truck_and_bus");
has_twist_ = this->declare_parameter<bool>("has_twist");


class_names_ = this->declare_parameter<std::vector<std::string>>("class_names");
rename_car_to_truck_and_bus_ = this->declare_parameter("rename_car_to_truck_and_bus", false);
Expand Down
14 changes: 7 additions & 7 deletions perception/lidar_centerpoint_tvm/src/single_inference_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,18 +46,18 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode(
: Node("lidar_center_point_tvm", node_options), tf_buffer_(this->get_clock())
{
const float score_threshold =
static_cast<float>(this->declare_parameter<double>("score_threshold", 0.35));
static_cast<float>(this->declare_parameter<double>("post_process_params.score_threshold"));
const float circle_nms_dist_threshold =
static_cast<float>(this->declare_parameter<double>("circle_nms_dist_threshold", 1.5));
static_cast<float>(this->declare_parameter<double>("post_process_params.circle_nms_dist_threshold"));
const float yaw_norm_threshold =
static_cast<float>(this->declare_parameter<double>("yaw_norm_threshold", 0.0));
static_cast<float>(this->declare_parameter<double>("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<std::string>("densification_params.world_frame_id");
const int32_t densification_num_past_frames =
this->declare_parameter<int>("densification_params.num_past_frames");

class_names_ = this->declare_parameter<std::vector<std::string>>("class_names");
has_twist_ = this->declare_parameter("has_twist", false);
has_twist_ = this->declare_parameter<bool>("has_twist");
const std::size_t point_feature_size =
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("point_feature_size"));
const std::size_t max_voxel_size =
Expand Down

0 comments on commit dcde1b9

Please sign in to comment.