From c22a15d565c148696be928312786eef108f9d8c8 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 31 Jan 2024 11:15:49 +0000 Subject: [PATCH] style(pre-commit): autofix --- ...radar_crossing_objects_filter_is_noise.cpp | 70 +++++++++---------- 1 file changed, 35 insertions(+), 35 deletions(-) diff --git a/perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp b/perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp index 908a28583eab1..e0808d76494d4 100644 --- a/perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp +++ b/perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include "radar_crossing_objects_noise_filter/radar_crossing_objects_noise_filter_node.hpp" + #include std::shared_ptr get_node( @@ -21,26 +22,18 @@ std::shared_ptr(node_options); + std::make_shared( + node_options); return node; } - std::shared_ptr get_object( - float twist_x, float twist_y, float twist_z, - float orientation_x, float orientation_y, float orientation_z, float orientation_w, - float pose_x, float pose_y - ) + float twist_x, float twist_y, float twist_z, float orientation_x, float orientation_y, + float orientation_z, float orientation_w, float pose_x, float pose_y) { - - auto ret = - std::make_shared(); + auto ret = std::make_shared(); ret->kinematics.twist_with_covariance.twist.linear.x = static_cast(twist_x); ret->kinematics.twist_with_covariance.twist.linear.y = static_cast(twist_y); ret->kinematics.twist_with_covariance.twist.linear.z = static_cast(twist_z); @@ -67,28 +60,30 @@ TEST(RadarCrossingObjectsFilter, IsNoise) float orientation_w = 0.0; float pose_x = 1.0; float pose_y = 0.0; - auto object = get_object(twist_x, twist_y, twist_z, orientation_x, orientation_y, orientation_z, orientation_w, pose_x, pose_y); + auto object = get_object( + twist_x, twist_y, twist_z, orientation_x, orientation_y, orientation_z, orientation_w, pose_x, + pose_y); { float velocity_threshold = 40.0; - float angle_threshold = 1.0472; + float angle_threshold = 1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_TRUE(node->isNoise(*object)); } { float velocity_threshold = 40.0; - float angle_threshold = -1.0472; + float angle_threshold = -1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_TRUE(node->isNoise(*object)); } { float velocity_threshold = -40.0; - float angle_threshold = 1.0472; + float angle_threshold = 1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_TRUE(node->isNoise(*object)); } { float velocity_threshold = -40.0; - float angle_threshold = -1.0472; + float angle_threshold = -1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_TRUE(node->isNoise(*object)); } @@ -104,28 +99,30 @@ TEST(RadarCrossingObjectsFilter, IsNoise) float orientation_w = 0.0; float pose_x = 1.0; float pose_y = 2.0; - auto object = get_object(twist_x, twist_y, twist_z, orientation_x, orientation_y, orientation_z, orientation_w, pose_x, pose_y); + auto object = get_object( + twist_x, twist_y, twist_z, orientation_x, orientation_y, orientation_z, orientation_w, pose_x, + pose_y); { float velocity_threshold = 40.0; - float angle_threshold = 1.0472; + float angle_threshold = 1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } { float velocity_threshold = 40.0; - float angle_threshold = -1.0472; + float angle_threshold = -1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } { float velocity_threshold = -40.0; - float angle_threshold = 1.0472; + float angle_threshold = 1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } { float velocity_threshold = -40.0; - float angle_threshold = -1.0472; + float angle_threshold = -1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } @@ -141,28 +138,30 @@ TEST(RadarCrossingObjectsFilter, IsNoise) float orientation_w = 0.0; float pose_x = 1.0; float pose_y = 0.0; - auto object = get_object(twist_x, twist_y, twist_z, orientation_x, orientation_y, orientation_z, orientation_w, pose_x, pose_y); + auto object = get_object( + twist_x, twist_y, twist_z, orientation_x, orientation_y, orientation_z, orientation_w, pose_x, + pose_y); { float velocity_threshold = 40.0; - float angle_threshold = 1.0472; + float angle_threshold = 1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } { float velocity_threshold = 40.0; - float angle_threshold = -1.0472; + float angle_threshold = -1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } { float velocity_threshold = -40.0; - float angle_threshold = 1.0472; + float angle_threshold = 1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_TRUE(node->isNoise(*object)); } { float velocity_threshold = -40.0; - float angle_threshold = -1.0472; + float angle_threshold = -1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_TRUE(node->isNoise(*object)); } @@ -178,31 +177,32 @@ TEST(RadarCrossingObjectsFilter, IsNoise) float orientation_w = 0.0; float pose_x = 1.0; float pose_y = 2.0; - auto object = get_object(twist_x, twist_y, twist_z, orientation_x, orientation_y, orientation_z, orientation_w, pose_x, pose_y); + auto object = get_object( + twist_x, twist_y, twist_z, orientation_x, orientation_y, orientation_z, orientation_w, pose_x, + pose_y); { float velocity_threshold = 40.0; - float angle_threshold = 1.0472; + float angle_threshold = 1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } { float velocity_threshold = 40.0; - float angle_threshold = -1.0472; + float angle_threshold = -1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } { float velocity_threshold = -40.0; - float angle_threshold = 1.0472; + float angle_threshold = 1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } { float velocity_threshold = -40.0; - float angle_threshold = -1.0472; + float angle_threshold = -1.0472; auto node = get_node(angle_threshold, velocity_threshold); EXPECT_FALSE(node->isNoise(*object)); } } } -