Skip to content

Commit

Permalink
feat(pointpainting_fusion): add test for painting util (#7169)
Browse files Browse the repository at this point in the history
* add: unit test for inside bbox func

Signed-off-by: tzhong518 <sworgun@gmail.com>

* style(pre-commit): autofix

* fix: correct param name

Signed-off-by: tzhong518 <sworgun@gmail.com>

* add: comment

Signed-off-by: tzhong518 <sworgun@gmail.com>

---------

Signed-off-by: tzhong518 <sworgun@gmail.com>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
tzhong518 and pre-commit-ci[bot] committed Jul 5, 2024
1 parent 71fc4c3 commit 5ebaed7
Show file tree
Hide file tree
Showing 4 changed files with 71 additions and 7 deletions.
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(
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);
}

0 comments on commit 5ebaed7

Please sign in to comment.