Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(pointpainting_fusion): add test for painting util #7169

Merged
7 changes: 7 additions & 0 deletions perception/image_projection_based_fusion/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -172,6 +172,13 @@ if(BUILD_TESTING)
ament_auto_add_gtest(test_geometry
test/test_geometry.cpp
)
# test needed cuda, tensorRT and cudnn
if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
ament_auto_add_gtest(test_pointpainting
test/test_pointpainting_fusion.cpp
)
endif()

endif()

ament_auto_package(INSTALL_TO_SHARE
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,14 @@ namespace image_projection_based_fusion
{
using Label = autoware_perception_msgs::msg::ObjectClassification;

inline bool isInsideBbox(
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

zc means scaling, right?

  • I prefer more specific name like roi_expand_scaleor scale_factor
  • Current calculation will not properly expand original rois (see figure below)

How about following expression?

inline bool isInsideBbox(
  float proj_x, float proj_y, const sensor_msgs::msg::RegionOfInterest& roi, float scale_factor)
{
  // Calculate new width and height with scaling
  float new_width = roi.width * scale_factor;
  float new_height = roi.height * scale_factor;

  // Calculate new offsets to keep the center fixed
  float new_x_offset = roi.x_offset + (roi.width - new_width) / 2.0;
  float new_y_offset = roi.y_offset + (roi.height - new_height) / 2.0;

  // Check if the projected point is within the scaled ROI
  return proj_x >= new_x_offset && proj_x <= (new_x_offset + new_width) &&
         proj_y >= new_y_offset && proj_y <= (new_y_offset + new_height);
}

image

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

zc means the z-axis value of the pointcloud in the camera coordinate, the formula is commented here. zc is multified to the roi offset to avoid division calculation.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Now I understand your point. Would you mind add comment like below?

// z_c is scaling to normalize projection point

float proj_x, float proj_y, sensor_msgs::msg::RegionOfInterest roi, float zc)
{
// z_c is scaling to normalize projection point
return proj_x >= roi.x_offset * zc && proj_x <= (roi.x_offset + roi.width) * zc &&
proj_y >= roi.y_offset * zc && proj_y <= (roi.y_offset + roi.height) * zc;
}

class PointPaintingFusionNode
: public FusionNode<sensor_msgs::msg::PointCloud2, DetectedObjects, DetectedObjectsWithFeature>
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,13 +45,6 @@ Eigen::Affine3f _transformToEigen(const geometry_msgs::msg::Transform & t)
namespace image_projection_based_fusion
{

inline bool isInsideBbox(
float proj_x, float proj_y, sensor_msgs::msg::RegionOfInterest roi, float zc)
{
return proj_x >= roi.x_offset * zc && proj_x <= (roi.x_offset + roi.width) * zc &&
proj_y >= roi.y_offset * zc && proj_y <= (roi.y_offset + roi.height) * zc;
}

inline bool isVehicle(int label2d)
{
return label2d == autoware_perception_msgs::msg::ObjectClassification::CAR ||
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <image_projection_based_fusion/pointpainting_fusion/node.hpp>

#include <gtest/gtest.h>

sensor_msgs::msg::RegionOfInterest createRoi(
const int32_t x_offset, const int32_t y_offset, const int32_t width, const int32_t height)
{
sensor_msgs::msg::RegionOfInterest roi;
roi.x_offset = x_offset;
roi.y_offset = y_offset;
roi.width = width;
roi.height = height;
return roi;
}

TEST(isInsideBboxTest, Inside)
{
const sensor_msgs::msg::RegionOfInterest roi = createRoi(20, 20, 10, 10);
bool result = image_projection_based_fusion::isInsideBbox(25.0, 25.0, roi, 1.0);
EXPECT_TRUE(result);
}

TEST(isInsideBboxTest, Border)
{
const sensor_msgs::msg::RegionOfInterest roi = createRoi(20, 20, 10, 10);
bool result = image_projection_based_fusion::isInsideBbox(20.0, 30.0, roi, 1.0);
EXPECT_TRUE(result);
}

TEST(isInsideBboxTest, Outside)
{
const sensor_msgs::msg::RegionOfInterest roi = createRoi(20, 20, 10, 10);
bool result = image_projection_based_fusion::isInsideBbox(15.0, 15.0, roi, 1.0);
EXPECT_FALSE(result);
}

TEST(isInsideBboxTest, Zero)
{
const sensor_msgs::msg::RegionOfInterest roi = createRoi(0, 0, 0, 0);
bool result = image_projection_based_fusion::isInsideBbox(0.0, 0.0, roi, 1.0);
EXPECT_TRUE(result);
}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

[imo]
We can add test on roi expansion

TEST(isInsideBboxTest, Expand_Border)
{
  const sensor_msgs::msg::RegionOfInterest roi = createRoi(20, 20, 10, 10);
  bool result = image_projection_based_fusion::isInsideBbox(15.0, 15.0, roi, 2.0);
  EXPECT_TRUE(result);
}

Loading