Skip to content

Commit 9553414

Browse files
authored
fix(autoware_image_projection_based_fusion): detected object roi box projection fix (#9519)
* fix: detected object roi box projection fix 1. eliminate misuse of std::numeric_limits<double>::min() 2. fix roi range up to the image edges Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: fix roi range calculation in RoiDetectedObjectFusionNode Improve the calculation of the region of interest (ROI) in the RoiDetectedObjectFusionNode. The previous code had an issue where the ROI range was not correctly limited to the image edges. This fix ensures that the ROI is within the image boundaries by using the correct comparison operators for the x and y coordinates. Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 47bbb1c commit 9553414

File tree

1 file changed

+11
-14
lines changed
  • perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion

1 file changed

+11
-14
lines changed

perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp

+11-14
Original file line numberDiff line numberDiff line change
@@ -146,8 +146,7 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs(
146146
transformPoints(vertices, object2camera_affine, vertices_camera_coord);
147147
}
148148

149-
double min_x(std::numeric_limits<double>::max()), min_y(std::numeric_limits<double>::max()),
150-
max_x(std::numeric_limits<double>::min()), max_y(std::numeric_limits<double>::min());
149+
double min_x(image_width), min_y(image_height), max_x(0.0), max_y(0.0);
151150
std::size_t point_on_image_cnt = 0;
152151
for (const auto & point : vertices_camera_coord) {
153152
if (point.z() <= 0.0) {
@@ -164,8 +163,8 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs(
164163
max_y = std::max(proj_point.y(), max_y);
165164

166165
if (
167-
proj_point.x() >= 0 && proj_point.x() <= image_width - 1 && proj_point.y() >= 0 &&
168-
proj_point.y() <= image_height - 1) {
166+
proj_point.x() >= 0 && proj_point.x() < image_width && proj_point.y() >= 0 &&
167+
proj_point.y() < image_height) {
169168
point_on_image_cnt++;
170169

171170
if (debugger_) {
@@ -177,18 +176,16 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs(
177176
continue;
178177
}
179178

180-
min_x = std::max(min_x, 0.0);
181-
min_y = std::max(min_y, 0.0);
182-
max_x = std::min(max_x, image_width - 1);
183-
max_y = std::min(max_y, image_height - 1);
179+
const uint32_t idx_min_x = std::floor(std::max(min_x, 0.0));
180+
const uint32_t idx_min_y = std::floor(std::max(min_y, 0.0));
181+
const uint32_t idx_max_x = std::ceil(std::min(max_x, image_width));
182+
const uint32_t idx_max_y = std::ceil(std::min(max_y, image_height));
184183

185184
DetectedObjectWithFeature object_roi;
186-
object_roi.feature.roi.x_offset = static_cast<std::uint32_t>(min_x);
187-
object_roi.feature.roi.y_offset = static_cast<std::uint32_t>(min_y);
188-
object_roi.feature.roi.width =
189-
static_cast<std::uint32_t>(max_x) - static_cast<std::uint32_t>(min_x);
190-
object_roi.feature.roi.height =
191-
static_cast<std::uint32_t>(max_y) - static_cast<std::uint32_t>(min_y);
185+
object_roi.feature.roi.x_offset = idx_min_x;
186+
object_roi.feature.roi.y_offset = idx_min_y;
187+
object_roi.feature.roi.width = idx_max_x - idx_min_x;
188+
object_roi.feature.roi.height = idx_max_y - idx_min_y;
192189
object_roi.object = object;
193190
object_roi_map.insert(std::make_pair(obj_i, object_roi));
194191

0 commit comments

Comments
 (0)