@@ -29,6 +29,21 @@ namespace fs = ::std::experimental::filesystem;
29
29
30
30
namespace traffic_light
31
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
+
32
47
inline std::vector<float > toFloatVector (const std::vector<double > double_vector)
33
48
{
34
49
return std::vector<float >(double_vector.begin (), double_vector.end ());
@@ -206,7 +221,7 @@ float TrafficLightFineDetectorNodelet::evalMatchScore(
206
221
float max_score = 0 .0f ;
207
222
const sensor_msgs::msg::RegionOfInterest & expected_roi = roi_p.second .roi ;
208
223
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);
210
225
if (score >= max_score) {
211
226
max_score = score;
212
227
id2bestDetection[tlr_id] = detection;
0 commit comments