Skip to content

Commit 65884fa

Browse files
style(pre-commit): autofix
1 parent 4169f7b commit 65884fa

File tree

3 files changed

+58
-44
lines changed

3 files changed

+58
-44
lines changed

perception/lidar_centerpoint/test/test_detection_class_remapper.cpp

+8-15
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <gtest/gtest.h>
1615
#include <lidar_centerpoint/detection_class_remapper.hpp>
1716

17+
#include <gtest/gtest.h>
18+
1819
TEST(DetectionClassRemapperTest, MapClasses)
1920
{
2021
centerpoint::DetectionClassRemapper remapper;
@@ -26,16 +27,8 @@ TEST(DetectionClassRemapperTest, MapClasses)
2627
0, 0, 1, // TRUCK can be remapped to TRAILER
2728
0, 1, 0 // TRAILER can be remapped to TRUCK
2829
};
29-
std::vector<double> min_area_matrix = {
30-
0.0, 0.0, 0.0,
31-
0.0, 0.0, 10.0,
32-
0.0, 0.0, 0.0
33-
};
34-
std::vector<double> max_area_matrix = {
35-
0.0, 0.0, 0.0,
36-
0.0, 0.0, 999.0,
37-
0.0, 10.0, 0.0
38-
};
30+
std::vector<double> min_area_matrix = {0.0, 0.0, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0};
31+
std::vector<double> max_area_matrix = {0.0, 0.0, 0.0, 0.0, 0.0, 999.0, 0.0, 10.0, 0.0};
3932

4033
remapper.setParameters(allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix);
4134

@@ -92,8 +85,8 @@ TEST(DetectionClassRemapperTest, MapClasses)
9285
EXPECT_EQ(msg.objects[3].classification[0].label, 2);
9386
}
9487

95-
int main(int argc, char** argv)
88+
int main(int argc, char ** argv)
9689
{
97-
testing::InitGoogleTest(&argc, argv);
98-
return RUN_ALL_TESTS();
99-
}
90+
testing::InitGoogleTest(&argc, argv);
91+
return RUN_ALL_TESTS();
92+
}

perception/lidar_centerpoint/test/test_nms.cpp

+12-11
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,14 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <gtest/gtest.h>
1615
#include "lidar_centerpoint/postprocess/non_maximum_suppression.hpp"
1716

17+
#include <gtest/gtest.h>
18+
1819
using namespace centerpoint;
1920

20-
TEST(NonMaximumSuppressionTest, Apply) {
21+
TEST(NonMaximumSuppressionTest, Apply)
22+
{
2123
NonMaximumSuppression nms;
2224
NMSParams params;
2325
params.search_distance_2d_ = 1.0;
@@ -32,7 +34,7 @@ TEST(NonMaximumSuppressionTest, Apply) {
3234
autoware_auto_perception_msgs::msg::ObjectClassification obj1_classification;
3335
obj1_classification.label = 0; // Assuming "car" has label 0
3436
obj1_classification.probability = 1.0;
35-
input_objects[0].classification = {obj1_classification}; // Assuming "car" has label 0
37+
input_objects[0].classification = {obj1_classification}; // Assuming "car" has label 0
3638
input_objects[0].kinematics.pose_with_covariance.pose.position.x = 0.0;
3739
input_objects[0].kinematics.pose_with_covariance.pose.position.y = 0.0;
3840
input_objects[0].kinematics.pose_with_covariance.pose.orientation.x = 0.0;
@@ -47,7 +49,7 @@ TEST(NonMaximumSuppressionTest, Apply) {
4749
autoware_auto_perception_msgs::msg::ObjectClassification obj2_classification;
4850
obj2_classification.label = 0; // Assuming "car" has label 0
4951
obj2_classification.probability = 1.0;
50-
input_objects[1].classification = {obj2_classification}; // Assuming "car" has label 0
52+
input_objects[1].classification = {obj2_classification}; // Assuming "car" has label 0
5153
input_objects[1].kinematics.pose_with_covariance.pose.position.x = 0.5;
5254
input_objects[1].kinematics.pose_with_covariance.pose.position.y = 0.5;
5355
input_objects[1].kinematics.pose_with_covariance.pose.orientation.x = 0.0;
@@ -62,7 +64,7 @@ TEST(NonMaximumSuppressionTest, Apply) {
6264
autoware_auto_perception_msgs::msg::ObjectClassification obj3_classification;
6365
obj3_classification.label = 0; // Assuming "car" has label 0
6466
obj3_classification.probability = 1.0;
65-
input_objects[2].classification = {obj3_classification}; // Assuming "car" has label 0
67+
input_objects[2].classification = {obj3_classification}; // Assuming "car" has label 0
6668
input_objects[2].kinematics.pose_with_covariance.pose.position.x = 5.0;
6769
input_objects[2].kinematics.pose_with_covariance.pose.position.y = 5.0;
6870
input_objects[2].kinematics.pose_with_covariance.pose.orientation.x = 0.0;
@@ -77,7 +79,7 @@ TEST(NonMaximumSuppressionTest, Apply) {
7779
autoware_auto_perception_msgs::msg::ObjectClassification obj4_classification;
7880
obj4_classification.label = 1; // Assuming "pedestrian" has label 1
7981
obj4_classification.probability = 1.0;
80-
input_objects[3].classification = {obj4_classification}; // Assuming "pedestrian" has label 1
82+
input_objects[3].classification = {obj4_classification}; // Assuming "pedestrian" has label 1
8183
input_objects[3].kinematics.pose_with_covariance.pose.position.x = 0.0;
8284
input_objects[3].kinematics.pose_with_covariance.pose.position.y = 0.0;
8385
input_objects[3].kinematics.pose_with_covariance.pose.orientation.x = 0.0;
@@ -114,9 +116,8 @@ TEST(NonMaximumSuppressionTest, Apply) {
114116
EXPECT_TRUE(is_input_object_3_included);
115117
}
116118

117-
118-
int main(int argc, char** argv)
119+
int main(int argc, char ** argv)
119120
{
120-
testing::InitGoogleTest(&argc, argv);
121-
return RUN_ALL_TESTS();
122-
}
121+
testing::InitGoogleTest(&argc, argv);
122+
return RUN_ALL_TESTS();
123+
}

perception/lidar_centerpoint/test/test_ros_utils.cpp

+38-18
Original file line numberDiff line numberDiff line change
@@ -12,19 +12,20 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <gtest/gtest.h>
16-
1715
#include "lidar_centerpoint/ros_utils.hpp"
1816

17+
#include <gtest/gtest.h>
18+
1919
TEST(TestSuite, box3DToDetectedObject)
2020
{
21-
std::vector<std::string> class_names = {"CAR", "TRUCK", "BUS", "TRAILER", "BICYCLE", "MOTORBIKE", "PEDESTRIAN"};
22-
21+
std::vector<std::string> class_names = {"CAR", "TRUCK", "BUS", "TRAILER",
22+
"BICYCLE", "MOTORBIKE", "PEDESTRIAN"};
23+
2324
// Test case 1: Test with valid label, has_twist=true, has_variance=true
2425
{
2526
centerpoint::Box3D box3d;
2627
box3d.score = 0.8f;
27-
box3d.label = 0; // CAR
28+
box3d.label = 0; // CAR
2829
box3d.x = 1.0;
2930
box3d.y = 2.0;
3031
box3d.z = 3.0;
@@ -45,7 +46,8 @@ TEST(TestSuite, box3DToDetectedObject)
4546
centerpoint::box3DToDetectedObject(box3d, class_names, true, true, obj);
4647

4748
EXPECT_FLOAT_EQ(obj.existence_probability, 0.8f);
48-
EXPECT_EQ(obj.classification[0].label, autoware_auto_perception_msgs::msg::ObjectClassification::CAR);
49+
EXPECT_EQ(
50+
obj.classification[0].label, autoware_auto_perception_msgs::msg::ObjectClassification::CAR);
4951
EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.x, 1.0);
5052
EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.y, 2.0);
5153
EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.z, 3.0);
@@ -61,13 +63,15 @@ TEST(TestSuite, box3DToDetectedObject)
6163
{
6264
centerpoint::Box3D box3d;
6365
box3d.score = 0.5f;
64-
box3d.label = 10; // Invalid
66+
box3d.label = 10; // Invalid
6567

6668
autoware_auto_perception_msgs::msg::DetectedObject obj;
6769
centerpoint::box3DToDetectedObject(box3d, class_names, false, false, obj);
6870

6971
EXPECT_FLOAT_EQ(obj.existence_probability, 0.5f);
70-
EXPECT_EQ(obj.classification[0].label, autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN);
72+
EXPECT_EQ(
73+
obj.classification[0].label,
74+
autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN);
7175
EXPECT_FALSE(obj.kinematics.has_position_covariance);
7276
EXPECT_FALSE(obj.kinematics.has_twist);
7377
EXPECT_FALSE(obj.kinematics.has_twist_covariance);
@@ -76,14 +80,30 @@ TEST(TestSuite, box3DToDetectedObject)
7680

7781
TEST(TestSuite, getSemanticType)
7882
{
79-
EXPECT_EQ(centerpoint::getSemanticType("CAR"), autoware_auto_perception_msgs::msg::ObjectClassification::CAR);
80-
EXPECT_EQ(centerpoint::getSemanticType("TRUCK"), autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK);
81-
EXPECT_EQ(centerpoint::getSemanticType("BUS"), autoware_auto_perception_msgs::msg::ObjectClassification::BUS);
82-
EXPECT_EQ(centerpoint::getSemanticType("TRAILER"), autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER);
83-
EXPECT_EQ(centerpoint::getSemanticType("BICYCLE"), autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE);
84-
EXPECT_EQ(centerpoint::getSemanticType("MOTORBIKE"), autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE);
85-
EXPECT_EQ(centerpoint::getSemanticType("PEDESTRIAN"), autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN);
86-
EXPECT_EQ(centerpoint::getSemanticType("UNKNOWN"), autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN);
83+
EXPECT_EQ(
84+
centerpoint::getSemanticType("CAR"),
85+
autoware_auto_perception_msgs::msg::ObjectClassification::CAR);
86+
EXPECT_EQ(
87+
centerpoint::getSemanticType("TRUCK"),
88+
autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK);
89+
EXPECT_EQ(
90+
centerpoint::getSemanticType("BUS"),
91+
autoware_auto_perception_msgs::msg::ObjectClassification::BUS);
92+
EXPECT_EQ(
93+
centerpoint::getSemanticType("TRAILER"),
94+
autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER);
95+
EXPECT_EQ(
96+
centerpoint::getSemanticType("BICYCLE"),
97+
autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE);
98+
EXPECT_EQ(
99+
centerpoint::getSemanticType("MOTORBIKE"),
100+
autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE);
101+
EXPECT_EQ(
102+
centerpoint::getSemanticType("PEDESTRIAN"),
103+
autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN);
104+
EXPECT_EQ(
105+
centerpoint::getSemanticType("UNKNOWN"),
106+
autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN);
87107
}
88108

89109
TEST(TestSuite, convertPoseCovarianceMatrix)
@@ -114,8 +134,8 @@ TEST(TestSuite, convertTwistCovarianceMatrix)
114134
EXPECT_FLOAT_EQ(twist_covariance[7], 0.2);
115135
}
116136

117-
int main(int argc, char **argv)
137+
int main(int argc, char ** argv)
118138
{
119139
testing::InitGoogleTest(&argc, argv);
120140
return RUN_ALL_TESTS();
121-
}
141+
}

0 commit comments

Comments
 (0)