Skip to content

Commit 2f6f80c

Browse files
committed
Revert "Revert "feat(traffic_light_fine_detector): update function for waited IoU""
This reverts commit 0ffe4db.
1 parent a542a98 commit 2f6f80c

File tree

2 files changed

+16
-20
lines changed

2 files changed

+16
-20
lines changed

perception/traffic_light_fine_detector/include/traffic_light_fine_detector/nodelet.hpp

+15
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,21 @@ typedef struct Detection
5252

5353
namespace traffic_light
5454
{
55+
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+
}
69+
5570
class TrafficLightFineDetectorNodelet : public rclcpp::Node
5671
{
5772
using TrafficLightRoi = tier4_perception_msgs::msg::TrafficLightRoi;

perception/traffic_light_fine_detector/src/nodelet.cpp

+1-20
Original file line numberDiff line numberDiff line change
@@ -27,25 +27,6 @@ namespace fs = ::std::experimental::filesystem;
2727
#include <utility>
2828
#include <vector>
2929

30-
namespace
31-
{
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-
47-
} // namespace
48-
4930
namespace traffic_light
5031
{
5132
inline std::vector<float> toFloatVector(const std::vector<double> double_vector)
@@ -225,7 +206,7 @@ float TrafficLightFineDetectorNodelet::evalMatchScore(
225206
float max_score = 0.0f;
226207
const sensor_msgs::msg::RegionOfInterest & expected_roi = roi_p.second.roi;
227208
for (const tensorrt_yolox::Object & detection : id2detections[tlr_id]) {
228-
float score = ::calWeightedIou(expected_roi, detection);
209+
float score = traffic_light::calWeightedIou(expected_roi, detection);
229210
if (score >= max_score) {
230211
max_score = score;
231212
id2bestDetection[tlr_id] = detection;

0 commit comments

Comments
 (0)