diff --git a/perception/traffic_light_fine_detector/src/nodelet.cpp b/perception/traffic_light_fine_detector/src/nodelet.cpp index 8037dc5472fbe..e06ffcad66d21 100644 --- a/perception/traffic_light_fine_detector/src/nodelet.cpp +++ b/perception/traffic_light_fine_detector/src/nodelet.cpp @@ -32,12 +32,14 @@ namespace float calWeightedIou( const sensor_msgs::msg::RegionOfInterest & bbox1, const tensorrt_yolox::Object & bbox2) { - int x1 = std::max(static_cast(bbox1.x_offset), bbox2.x_offset); - int x2 = std::min(static_cast(bbox1.x_offset + bbox1.width), bbox2.x_offset + bbox2.width); - int y1 = std::max(static_cast(bbox1.y_offset), bbox2.y_offset); - int y2 = std::min(static_cast(bbox1.y_offset + bbox1.height), bbox2.y_offset + bbox2.height); - int area1 = std::max(x2 - x1, 0) * std::max(y2 - y1, 0); - int area2 = bbox1.width * bbox1.height + bbox2.width * bbox2.height - area1; + const int x1 = std::max(static_cast(bbox1.x_offset), bbox2.x_offset); + const int x2 = + std::min(static_cast(bbox1.x_offset + bbox1.width), bbox2.x_offset + bbox2.width); + const int y1 = std::max(static_cast(bbox1.y_offset), bbox2.y_offset); + const int y2 = + std::min(static_cast(bbox1.y_offset + bbox1.height), bbox2.y_offset + bbox2.height); + const int area1 = std::max(x2 - x1, 0) * std::max(y2 - y1, 0); + const int area2 = bbox1.width * bbox1.height + bbox2.width * bbox2.height - area1; if (area2 == 0) { return 0.0; }