Skip to content

Commit 4c941e3

Browse files
committed
Revert "Revert "feat(traffic_light_fine_detector): move definition of util function to cpp""
This reverts commit 85aeaa4.
1 parent 2f6f80c commit 4c941e3

File tree

2 files changed

+17
-14
lines changed

2 files changed

+17
-14
lines changed

perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp

+1-13
Original file line numberDiff line numberDiff line change
@@ -53,19 +53,7 @@ typedef struct Detection
5353
namespace traffic_light
5454
{
5555
float calWeightedIou(
56-
const sensor_msgs::msg::RegionOfInterest & bbox1, const tensorrt_yolox::Object & bbox2)
57-
{
58-
int x1 = std::max(static_cast<int>(bbox1.x_offset), bbox2.x_offset);
59-
int x2 = std::min(static_cast<int>(bbox1.x_offset + bbox1.width), bbox2.x_offset + bbox2.width);
60-
int y1 = std::max(static_cast<int>(bbox1.y_offset), bbox2.y_offset);
61-
int y2 = std::min(static_cast<int>(bbox1.y_offset + bbox1.height), bbox2.y_offset + bbox2.height);
62-
int area1 = std::max(x2 - x1, 0) * std::max(y2 - y1, 0);
63-
int area2 = bbox1.width * bbox1.height + bbox2.width * bbox2.height - area1;
64-
if (area2 == 0) {
65-
return 0.0;
66-
}
67-
return bbox2.score * area1 / area2;
68-
}
56+
const sensor_msgs::msg::RegionOfInterest & bbox1, const tensorrt_yolox::Object & bbox2);
6957

7058
class TrafficLightFineDetectorNodelet : public rclcpp::Node
7159
{

perception/traffic_light_fine_detector/src/nodelet.cpp

+16-1
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,21 @@ namespace fs = ::std::experimental::filesystem;
2929

3030
namespace traffic_light
3131
{
32+
float calWeightedIou(
33+
const sensor_msgs::msg::RegionOfInterest & bbox1, const tensorrt_yolox::Object & bbox2)
34+
{
35+
int x1 = std::max(static_cast<int>(bbox1.x_offset), bbox2.x_offset);
36+
int x2 = std::min(static_cast<int>(bbox1.x_offset + bbox1.width), bbox2.x_offset + bbox2.width);
37+
int y1 = std::max(static_cast<int>(bbox1.y_offset), bbox2.y_offset);
38+
int y2 = std::min(static_cast<int>(bbox1.y_offset + bbox1.height), bbox2.y_offset + bbox2.height);
39+
int area1 = std::max(x2 - x1, 0) * std::max(y2 - y1, 0);
40+
int area2 = bbox1.width * bbox1.height + bbox2.width * bbox2.height - area1;
41+
if (area2 == 0) {
42+
return 0.0;
43+
}
44+
return bbox2.score * area1 / area2;
45+
}
46+
3247
inline std::vector<float> toFloatVector(const std::vector<double> double_vector)
3348
{
3449
return std::vector<float>(double_vector.begin(), double_vector.end());
@@ -206,7 +221,7 @@ float TrafficLightFineDetectorNodelet::evalMatchScore(
206221
float max_score = 0.0f;
207222
const sensor_msgs::msg::RegionOfInterest & expected_roi = roi_p.second.roi;
208223
for (const tensorrt_yolox::Object & detection : id2detections[tlr_id]) {
209-
float score = traffic_light::calWeightedIou(expected_roi, detection);
224+
float score = calWeightedIou(expected_roi, detection);
210225
if (score >= max_score) {
211226
max_score = score;
212227
id2bestDetection[tlr_id] = detection;

0 commit comments

Comments
 (0)