Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 378ef6d

Browse files
committedMay 22, 2024·
style(pre-commit): autofix
1 parent 3061a2c commit 378ef6d

File tree

1 file changed

+11
-12
lines changed

1 file changed

+11
-12
lines changed
 

‎perception/image_projection_based_fusion/test/test_geometry.cpp

+11-12
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,7 @@
1717
#include <glog/logging.h>
1818
#include <gtest/gtest.h>
1919

20-
TEST(objectToVertices,
21-
test_objectToVertices)
20+
TEST(objectToVertices, test_objectToVertices)
2221
{
2322
// Test `boundingBoxToVertices()` and `cylinderToVertices()` simultaneously
2423
// Test at Shape::BOUNDING_BOX
@@ -71,14 +70,16 @@ test_objectToVertices)
7170
EXPECT_TRUE(vertices.empty());
7271
}
7372

74-
TEST(transformPoints,
75-
test_transformPoints)
73+
TEST(transformPoints, test_transformPoints)
7674
{
7775
std::vector<Eigen::Vector3d> input_points;
7876
Eigen::Vector3d point(0.0, 0.0, 0.0);
7977
input_points.push_back(point);
8078
Eigen::Translation<double, 3> translation(1.0, 1.0, 1.0);
81-
Eigen::Matrix3d rotation = (Eigen::AngleAxisd(M_PI/4, Eigen::Vector3d::UnitX()) * Eigen::AngleAxisd(M_PI/4, Eigen::Vector3d::UnitY()) * Eigen::AngleAxisd(M_PI/4, Eigen::Vector3d::UnitZ())).toRotationMatrix();
79+
Eigen::Matrix3d rotation = (Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitX()) *
80+
Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitY()) *
81+
Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitZ()))
82+
.toRotationMatrix();
8283
Eigen::Affine3d affine_transform = rotation * translation;
8384
std::vector<Eigen::Vector3d> output_points;
8485

@@ -90,8 +91,7 @@ test_transformPoints)
9091
EXPECT_NEAR(output_points.at(0).z(), 1.5, 1e-6);
9192
}
9293

93-
TEST(is_inside,
94-
test_is_inside)
94+
TEST(is_inside, test_is_inside)
9595
{
9696
// Test default pattern
9797
sensor_msgs::msg::RegionOfInterest outer;
@@ -129,17 +129,16 @@ test_is_inside)
129129
EXPECT_FALSE(inside_flag);
130130
}
131131

132-
TEST(sanitizeROI,
133-
test_sanitizeROI)
132+
TEST(sanitizeROI, test_sanitizeROI)
134133
{
135134
// Test default pattern
136135
sensor_msgs::msg::RegionOfInterest roi;
137136
roi.x_offset = 10;
138137
roi.y_offset = 20;
139138
roi.height = 200;
140139
roi.width = 100;
141-
int height_ = 400; // image height
142-
int width_ = 300; // image width
140+
int height_ = 400; // image height
141+
int width_ = 300; // image width
143142

144143
image_projection_based_fusion::sanitizeROI(roi, width_, height_);
145144

@@ -156,7 +155,7 @@ test_sanitizeROI)
156155

157156
EXPECT_EQ(roi.height, 0);
158157
EXPECT_EQ(roi.width, 0);
159-
158+
160159
// Test patten that roi does not fit within image
161160
roi.x_offset = 10;
162161
roi.y_offset = 20;

0 commit comments

Comments
 (0)
Please sign in to comment.