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

feat(lidar_transfusion): update TransFusion-L model (#7890) #1479

Open
wants to merge 1 commit into
base: beta/v0.29.0
Choose a base branch
from
Open
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
4 changes: 2 additions & 2 deletions perception/lidar_transfusion/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,9 @@ ros2 launch lidar_transfusion lidar_transfusion.launch.xml log_level:=debug

You can download the onnx format of trained models by clicking on the links below.

- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/v1/transfusion.onnx)
- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/t4xx1_90m/v2/transfusion.onnx)

The model was trained in TIER IV's internal database (~11k lidar frames) for 20 epochs.
The model was trained in TIER IV's internal database (~11k lidar frames) for 50 epochs.

### Changelog

Expand Down
7 changes: 4 additions & 3 deletions perception/lidar_transfusion/config/transfusion.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,9 @@
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
trt_precision: fp16
voxels_num: [5000, 30000, 60000] # [min, opt, max]
point_cloud_range: [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0] # [x_min, y_min, z_min, x_max, y_max, z_max]
voxel_size: [0.3, 0.3, 8.0] # [x, y, z]
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]
num_proposals: 500
onnx_path: "$(var model_path)/transfusion.onnx"
engine_path: "$(var model_path)/transfusion.engine"
# pre-process params
Expand All @@ -17,4 +18,4 @@
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # refers to the class_names
score_threshold: 0.2
score_threshold: 0.1
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,9 @@ class TransfusionConfig
public:
TransfusionConfig(
const std::vector<int64_t> & voxels_num, const std::vector<double> & point_cloud_range,
const std::vector<double> & voxel_size, const float circle_nms_dist_threshold,
const std::vector<double> & yaw_norm_thresholds, const float score_threshold)
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)
{
if (voxels_num.size() == 3) {
max_voxels_ = voxels_num[2];
Expand Down Expand Up @@ -61,6 +62,9 @@ class TransfusionConfig
voxel_y_size_ = static_cast<float>(voxel_size[1]);
voxel_z_size_ = static_cast<float>(voxel_size[2]);
}
if (num_proposals > 0) {
num_proposals_ = num_proposals;
}
if (score_threshold > 0.0) {
score_threshold_ = score_threshold;
}
Expand All @@ -76,6 +80,9 @@ class TransfusionConfig
grid_x_size_ = static_cast<std::size_t>((max_x_range_ - min_x_range_) / voxel_x_size_);
grid_y_size_ = static_cast<std::size_t>((max_y_range_ - min_y_range_) / voxel_y_size_);
grid_z_size_ = static_cast<std::size_t>((max_z_range_ - min_z_range_) / voxel_z_size_);

feature_x_size_ = grid_x_size_ / out_size_factor_;
feature_y_size_ = grid_y_size_ / out_size_factor_;
}

///// INPUT PARAMETERS /////
Expand Down Expand Up @@ -107,7 +114,7 @@ class TransfusionConfig
const std::size_t out_size_factor_{4};
const std::size_t max_num_points_per_pillar_{points_per_voxel_};
const std::size_t num_point_values_{4};
const std::size_t num_proposals_{200};
std::size_t num_proposals_{200};
// the number of feature maps for pillar scatter
const std::size_t num_feature_scatter_{pillar_feature_size_};
// the score threshold for classification
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 @@ -61,6 +61,12 @@
"default": "$(var model_path)/transfusion.engine",
"pattern": "\\.engine$"
},
"num_proposals": {
"type": "integer",
"description": "Number of proposals at TransHead.",
"default": 500,
"minimum": 1
},
"down_sample_factor": {
"type": "integer",
"description": "A scale factor of downsampling points",
Expand Down
5 changes: 3 additions & 2 deletions perception/lidar_transfusion/src/lidar_transfusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options)
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::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 @@ -73,8 +74,8 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options)
DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);
TransfusionConfig config(
voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds,
score_threshold);
voxels_num, point_cloud_range, voxel_size, num_proposals, circle_nms_dist_threshold,
yaw_norm_thresholds, score_threshold);

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