Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: ml detector buffer capacity and parameterization #7936

Merged
merged 6 commits into from
Jul 17, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
trt_precision: fp16
cloud_capacity: 2000000
post_process_params:
# post-process params
circle_nms_dist_threshold: 0.3
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

namespace image_projection_based_fusion
{
static constexpr size_t CAPACITY_POINT = 1000000;
class PointPaintingTRT : public centerpoint::CenterPointTRT
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,7 @@
this->declare_parameter<int>("densification_params.num_past_frames");
// network param
const std::string trt_precision = this->declare_parameter<std::string>("trt_precision");
const std::size_t cloud_capacity = this->declare_parameter<std::int64_t>("cloud_capacity");

Check warning on line 106 in perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L106

Added line #L106 was not covered by tests
const std::string encoder_onnx_path = this->declare_parameter<std::string>("encoder_onnx_path");
const std::string encoder_engine_path =
this->declare_parameter<std::string>("encoder_engine_path");
Expand Down Expand Up @@ -181,9 +182,9 @@
centerpoint::DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);
centerpoint::CenterPointConfig config(
class_names_.size(), point_feature_size, max_voxel_size, pointcloud_range, voxel_size,
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
yaw_norm_thresholds, has_variance_);
class_names_.size(), point_feature_size, cloud_capacity, max_voxel_size, pointcloud_range,
voxel_size, downsample_factor, encoder_in_feature_size, score_threshold,
circle_nms_dist_threshold, yaw_norm_thresholds, has_variance_);

Check warning on line 187 in perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L187

Added line #L187 was not covered by tests

// create detector
detector_ptr_ = std::make_unique<image_projection_based_fusion::PointPaintingTRT>(
Expand Down
1 change: 1 addition & 0 deletions perception/lidar_centerpoint/config/centerpoint.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
trt_precision: fp16
cloud_capacity: 2000000
post_process_params:
# post-process params
circle_nms_dist_threshold: 0.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
trt_precision: fp16
cloud_capacity: 2000000
post_process_params:
# post-process params
circle_nms_dist_threshold: 0.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,16 @@
{
public:
explicit CenterPointConfig(
const std::size_t class_size, const float point_feature_size, const std::size_t max_voxel_size,
const std::vector<double> & point_cloud_range, const std::vector<double> & voxel_size,
const std::size_t downsample_factor, const std::size_t encoder_in_feature_size,
const float score_threshold, const float circle_nms_dist_threshold,
const std::vector<double> yaw_norm_thresholds, const bool has_variance)
const std::size_t class_size, const float point_feature_size, const std::size_t cloud_capacity,
const std::size_t max_voxel_size, const std::vector<double> & point_cloud_range,
const std::vector<double> & voxel_size, const std::size_t downsample_factor,
const std::size_t encoder_in_feature_size, const float score_threshold,
const float circle_nms_dist_threshold, const std::vector<double> yaw_norm_thresholds,
const bool has_variance)
{
class_size_ = class_size;
point_feature_size_ = point_feature_size;
cloud_capacity_ = cloud_capacity;

Check warning on line 36 in perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_config.hpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_config.hpp#L36

Added line #L36 was not covered by tests
max_voxel_size_ = max_voxel_size;
if (point_cloud_range.size() == 6) {
range_min_x_ = static_cast<float>(point_cloud_range[0]);
Expand Down Expand Up @@ -85,6 +87,7 @@
};

// input params
std::size_t cloud_capacity_{};
std::size_t class_size_{3};
const std::size_t point_dim_size_{3}; // x, y and z
std::size_t point_feature_size_{4}; // x, y, z and time-lag
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,6 @@

namespace centerpoint
{
static constexpr size_t CAPACITY_POINT = 1000000;

class NetworkParam
{
public:
Expand Down
4 changes: 2 additions & 2 deletions perception/lidar_centerpoint/lib/centerpoint_trt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@
mask_size_ = config_.grid_size_x_ * config_.grid_size_y_;

// host
points_.resize(CAPACITY_POINT * config_.point_feature_size_);
points_.resize(config_.cloud_capacity_ * config_.point_feature_size_);

Check warning on line 88 in perception/lidar_centerpoint/lib/centerpoint_trt.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/centerpoint_trt.cpp#L88

Added line #L88 was not covered by tests

// device
voxels_d_ = cuda::make_unique<float[]>(voxels_size_);
Expand All @@ -100,7 +100,7 @@
head_out_dim_d_ = cuda::make_unique<float[]>(grid_xy_size * config_.head_out_dim_size_);
head_out_rot_d_ = cuda::make_unique<float[]>(grid_xy_size * config_.head_out_rot_size_);
head_out_vel_d_ = cuda::make_unique<float[]>(grid_xy_size * config_.head_out_vel_size_);
points_d_ = cuda::make_unique<float[]>(CAPACITY_POINT * config_.point_feature_size_);
points_d_ = cuda::make_unique<float[]>(config_.cloud_capacity_ * config_.point_feature_size_);

Check warning on line 103 in perception/lidar_centerpoint/lib/centerpoint_trt.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/centerpoint_trt.cpp#L103

Added line #L103 was not covered by tests
voxels_buffer_d_ = cuda::make_unique<float[]>(voxels_buffer_size_);
mask_d_ = cuda::make_unique<unsigned int[]>(mask_size_);
num_voxels_d_ = cuda::make_unique<unsigned int[]>(1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ std::size_t VoxelGenerator::generateSweepPoints(float * points_d, cudaStream_t s
float time_lag = static_cast<float>(
pd_ptr_->getCurrentTimestamp() - rclcpp::Time(pc_cache_iter->header.stamp).seconds());

if (point_counter + sweep_num_points > CAPACITY_POINT) {
if (point_counter + sweep_num_points > config_.cloud_capacity_) {
RCLCPP_WARN_STREAM(
rclcpp::get_logger("lidar_centerpoint"),
"Requested number of points exceeds the maximum capacity. Current points = "
Expand Down
6 changes: 6 additions & 0 deletions perception/lidar_centerpoint/schema/centerpoint.schemal.json
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,12 @@
"default": "fp16",
"enum": ["fp32", "fp16"]
},
"cloud_capacity": {
"type": "integer",
"description": "Capacity of the point cloud buffer (should be set to at least the maximum theoretical number of points).",
"default": 2000000,
"minimum": 1
},
"post_process_params": {
"type": "object",
"properties": {
Expand Down
7 changes: 4 additions & 3 deletions perception/lidar_centerpoint/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
const int densification_num_past_frames =
this->declare_parameter<int>("densification_params.num_past_frames");
const std::string trt_precision = this->declare_parameter<std::string>("trt_precision");
const std::size_t cloud_capacity = this->declare_parameter<std::int64_t>("cloud_capacity");

Check warning on line 53 in perception/lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/src/node.cpp#L53

Added line #L53 was not covered by tests
const std::string encoder_onnx_path = this->declare_parameter<std::string>("encoder_onnx_path");
const std::string encoder_engine_path =
this->declare_parameter<std::string>("encoder_engine_path");
Expand Down Expand Up @@ -104,9 +105,9 @@
"The size of voxel_size != 3: use the default parameters.");
}
CenterPointConfig config(
class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
yaw_norm_thresholds, has_variance_);
class_names_.size(), point_feature_size, cloud_capacity, max_voxel_size, point_cloud_range,
voxel_size, downsample_factor, encoder_in_feature_size, score_threshold,
circle_nms_dist_threshold, yaw_norm_thresholds, has_variance_);

Check warning on line 110 in perception/lidar_centerpoint/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

LidarCenterPointNode::LidarCenterPointNode increases from 89 to 90 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 110 in perception/lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/src/node.cpp#L110

Added line #L110 was not covered by tests
detector_ptr_ =
std::make_unique<CenterPointTRT>(encoder_param, head_param, densification_param, config);

Expand Down
1 change: 1 addition & 0 deletions perception/lidar_transfusion/config/transfusion.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
# network
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
trt_precision: fp16
cloud_capacity: 2000000
voxels_num: [5000, 30000, 60000] # [min, opt, max]
point_cloud_range: [-92.16, -92.16, -3.0, 92.16, 92.16, 7.0] # [x_min, y_min, z_min, x_max, y_max, z_max]
voxel_size: [0.24, 0.24, 10.0] # [x, y, z]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,13 @@
{
public:
TransfusionConfig(
const std::vector<int64_t> & voxels_num, const std::vector<double> & point_cloud_range,
const std::vector<double> & voxel_size, const int num_proposals,
const float circle_nms_dist_threshold, const std::vector<double> & yaw_norm_thresholds,
const float score_threshold)
const std::size_t cloud_capacity, const std::vector<int64_t> & voxels_num,
const std::vector<double> & point_cloud_range, const std::vector<double> & voxel_size,
const std::size_t num_proposals, const float circle_nms_dist_threshold,
const std::vector<double> & yaw_norm_thresholds, const float score_threshold)
{
cloud_capacity_ = cloud_capacity;

Check warning on line 33 in perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp#L33

Added line #L33 was not covered by tests

if (voxels_num.size() == 3) {
max_voxels_ = voxels_num[2];

Expand Down Expand Up @@ -86,7 +88,7 @@
}

///// INPUT PARAMETERS /////
const std::size_t cloud_capacity_{1000000};
std::size_t cloud_capacity_{};
///// KERNEL PARAMETERS /////
const std::size_t threads_for_voxel_{256}; // threads number for a block
const std::size_t points_per_voxel_{20};
Expand Down
6 changes: 6 additions & 0 deletions perception/lidar_transfusion/schema/transfusion.schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,12 @@
"default": "fp16",
"enum": ["fp16", "fp32"]
},
"cloud_capacity": {
"type": "integer",
"description": "Capacity of the point cloud buffer (should be set to at least the maximum theoretical number of points).",
"default": 2000000,
"minimum": 1
},
"voxels_num": {
"type": "array",
"items": {
Expand Down
9 changes: 6 additions & 3 deletions perception/lidar_transfusion/src/lidar_transfusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,14 @@
class_names_ = this->declare_parameter<std::vector<std::string>>("class_names", descriptor);
const std::string trt_precision =
this->declare_parameter<std::string>("trt_precision", descriptor);
const std::size_t cloud_capacity =
this->declare_parameter<std::int64_t>("cloud_capacity", descriptor);

Check warning on line 31 in perception/lidar_transfusion/src/lidar_transfusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_transfusion/src/lidar_transfusion_node.cpp#L31

Added line #L31 was not covered by tests
const auto voxels_num = this->declare_parameter<std::vector<int64_t>>("voxels_num", descriptor);
const auto point_cloud_range =
this->declare_parameter<std::vector<double>>("point_cloud_range", descriptor);
const auto voxel_size = this->declare_parameter<std::vector<double>>("voxel_size", descriptor);
const int num_proposals = (this->declare_parameter<int>("num_proposals", descriptor));
const std::size_t num_proposals =
this->declare_parameter<std::int64_t>("num_proposals", descriptor);

Check warning on line 37 in perception/lidar_transfusion/src/lidar_transfusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_transfusion/src/lidar_transfusion_node.cpp#L37

Added line #L37 was not covered by tests
const std::string onnx_path = this->declare_parameter<std::string>("onnx_path", descriptor);
const std::string engine_path = this->declare_parameter<std::string>("engine_path", descriptor);

Expand Down Expand Up @@ -74,8 +77,8 @@
DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);
TransfusionConfig config(
voxels_num, point_cloud_range, voxel_size, num_proposals, circle_nms_dist_threshold,
yaw_norm_thresholds, score_threshold);
cloud_capacity, voxels_num, point_cloud_range, voxel_size, num_proposals,
circle_nms_dist_threshold, yaw_norm_thresholds, score_threshold);

Check warning on line 81 in perception/lidar_transfusion/src/lidar_transfusion_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

LidarTransfusionNode::LidarTransfusionNode increases from 78 to 81 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 81 in perception/lidar_transfusion/src/lidar_transfusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_transfusion/src/lidar_transfusion_node.cpp#L81

Added line #L81 was not covered by tests

const auto allow_remapping_by_area_matrix =
this->declare_parameter<std::vector<int64_t>>("allow_remapping_by_area_matrix", descriptor);
Expand Down
Loading