Skip to content

Commit c507d8f

Browse files
committed
Revert "feat(lidar_transfusion): update TransFusion-L model (autowarefoundation#7890)"
This reverts commit 1f01a7c.
1 parent 9943996 commit c507d8f

File tree

5 files changed

+10
-25
lines changed

5 files changed

+10
-25
lines changed

perception/lidar_transfusion/README.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -81,9 +81,9 @@ ros2 topic echo <input_topic> --field fields
8181

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

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

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

8888
### Changelog
8989

perception/lidar_transfusion/config/transfusion.param.yaml

+3-4
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,8 @@
44
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
55
trt_precision: fp16
66
voxels_num: [5000, 30000, 60000] # [min, opt, max]
7-
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]
8-
voxel_size: [0.24, 0.24, 10.0] # [x, y, z]
9-
num_proposals: 500
7+
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]
8+
voxel_size: [0.3, 0.3, 8.0] # [x, y, z]
109
onnx_path: "$(var model_path)/transfusion.onnx"
1110
engine_path: "$(var model_path)/transfusion.engine"
1211
# pre-process params
@@ -18,4 +17,4 @@
1817
iou_nms_search_distance_2d: 10.0
1918
iou_nms_threshold: 0.1
2019
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # refers to the class_names
21-
score_threshold: 0.1
20+
score_threshold: 0.2

perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp

+3-10
Original file line numberDiff line numberDiff line change
@@ -26,9 +26,8 @@ class TransfusionConfig
2626
public:
2727
TransfusionConfig(
2828
const std::vector<int64_t> & voxels_num, const std::vector<double> & point_cloud_range,
29-
const std::vector<double> & voxel_size, const int num_proposals,
30-
const float circle_nms_dist_threshold, const std::vector<double> & yaw_norm_thresholds,
31-
const float score_threshold)
29+
const std::vector<double> & voxel_size, const float circle_nms_dist_threshold,
30+
const std::vector<double> & yaw_norm_thresholds, const float score_threshold)
3231
{
3332
if (voxels_num.size() == 3) {
3433
max_voxels_ = voxels_num[2];
@@ -62,9 +61,6 @@ class TransfusionConfig
6261
voxel_y_size_ = static_cast<float>(voxel_size[1]);
6362
voxel_z_size_ = static_cast<float>(voxel_size[2]);
6463
}
65-
if (num_proposals > 0) {
66-
num_proposals_ = num_proposals;
67-
}
6864
if (score_threshold > 0.0) {
6965
score_threshold_ = score_threshold;
7066
}
@@ -80,9 +76,6 @@ class TransfusionConfig
8076
grid_x_size_ = static_cast<std::size_t>((max_x_range_ - min_x_range_) / voxel_x_size_);
8177
grid_y_size_ = static_cast<std::size_t>((max_y_range_ - min_y_range_) / voxel_y_size_);
8278
grid_z_size_ = static_cast<std::size_t>((max_z_range_ - min_z_range_) / voxel_z_size_);
83-
84-
feature_x_size_ = grid_x_size_ / out_size_factor_;
85-
feature_y_size_ = grid_y_size_ / out_size_factor_;
8679
}
8780

8881
///// INPUT PARAMETERS /////
@@ -114,7 +107,7 @@ class TransfusionConfig
114107
const std::size_t out_size_factor_{4};
115108
const std::size_t max_num_points_per_pillar_{points_per_voxel_};
116109
const std::size_t num_point_values_{4};
117-
std::size_t num_proposals_{200};
110+
const std::size_t num_proposals_{200};
118111
// the number of feature maps for pillar scatter
119112
const std::size_t num_feature_scatter_{pillar_feature_size_};
120113
// the score threshold for classification

perception/lidar_transfusion/schema/transfusion.schema.json

-6
Original file line numberDiff line numberDiff line change
@@ -61,12 +61,6 @@
6161
"default": "$(var model_path)/transfusion.engine",
6262
"pattern": "\\.engine$"
6363
},
64-
"num_proposals": {
65-
"type": "integer",
66-
"description": "Number of proposals at TransHead.",
67-
"default": 500,
68-
"minimum": 1
69-
},
7064
"down_sample_factor": {
7165
"type": "integer",
7266
"description": "A scale factor of downsampling points",

perception/lidar_transfusion/src/lidar_transfusion_node.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,6 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options)
3131
const auto point_cloud_range =
3232
this->declare_parameter<std::vector<double>>("point_cloud_range", descriptor);
3333
const auto voxel_size = this->declare_parameter<std::vector<double>>("voxel_size", descriptor);
34-
const int num_proposals = (this->declare_parameter<int>("num_proposals", descriptor));
3534
const std::string onnx_path = this->declare_parameter<std::string>("onnx_path", descriptor);
3635
const std::string engine_path = this->declare_parameter<std::string>("engine_path", descriptor);
3736

@@ -74,8 +73,8 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options)
7473
DensificationParam densification_param(
7574
densification_world_frame_id, densification_num_past_frames);
7675
TransfusionConfig config(
77-
voxels_num, point_cloud_range, voxel_size, num_proposals, circle_nms_dist_threshold,
78-
yaw_norm_thresholds, score_threshold);
76+
voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds,
77+
score_threshold);
7978

8079
const auto allow_remapping_by_area_matrix =
8180
this->declare_parameter<std::vector<int64_t>>("allow_remapping_by_area_matrix", descriptor);

0 commit comments

Comments
 (0)