Skip to content

Commit

Permalink
fix(autoware_image_projection_based_fusion): detected object roi box …
Browse files Browse the repository at this point in the history
…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 <[email protected]>

* 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 <[email protected]>

---------

Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin authored Dec 9, 2024
1 parent 47bbb1c commit 9553414
Showing 1 changed file with 11 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -146,8 +146,7 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs(
transformPoints(vertices, object2camera_affine, vertices_camera_coord);
}

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

if (
proj_point.x() >= 0 && proj_point.x() <= image_width - 1 && proj_point.y() >= 0 &&
proj_point.y() <= image_height - 1) {
proj_point.x() >= 0 && proj_point.x() < image_width && proj_point.y() >= 0 &&
proj_point.y() < image_height) {
point_on_image_cnt++;

if (debugger_) {
Expand All @@ -177,18 +176,16 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs(
continue;
}

min_x = std::max(min_x, 0.0);
min_y = std::max(min_y, 0.0);
max_x = std::min(max_x, image_width - 1);
max_y = std::min(max_y, image_height - 1);
const uint32_t idx_min_x = std::floor(std::max(min_x, 0.0));
const uint32_t idx_min_y = std::floor(std::max(min_y, 0.0));
const uint32_t idx_max_x = std::ceil(std::min(max_x, image_width));
const uint32_t idx_max_y = std::ceil(std::min(max_y, image_height));

DetectedObjectWithFeature object_roi;
object_roi.feature.roi.x_offset = static_cast<std::uint32_t>(min_x);
object_roi.feature.roi.y_offset = static_cast<std::uint32_t>(min_y);
object_roi.feature.roi.width =
static_cast<std::uint32_t>(max_x) - static_cast<std::uint32_t>(min_x);
object_roi.feature.roi.height =
static_cast<std::uint32_t>(max_y) - static_cast<std::uint32_t>(min_y);
object_roi.feature.roi.x_offset = idx_min_x;
object_roi.feature.roi.y_offset = idx_min_y;
object_roi.feature.roi.width = idx_max_x - idx_min_x;
object_roi.feature.roi.height = idx_max_y - idx_min_y;
object_roi.object = object;
object_roi_map.insert(std::make_pair(obj_i, object_roi));

Expand Down

0 comments on commit 9553414

Please sign in to comment.