Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jan 31, 2024
1 parent fb93d2c commit c22a15d
Showing 1 changed file with 35 additions and 35 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include "radar_crossing_objects_noise_filter/radar_crossing_objects_noise_filter_node.hpp"

#include <gtest/gtest.h>

std::shared_ptr<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode> get_node(
Expand All @@ -21,26 +22,18 @@ std::shared_ptr<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFi
rclcpp::NodeOptions node_options;

node_options.parameter_overrides(
{
{"angle_threshold", angle_threshold},
{"velocity_threshold", velocity_threshold}
}
);
{{"angle_threshold", angle_threshold}, {"velocity_threshold", velocity_threshold}});
auto node =
std::make_shared<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode>(node_options);
std::make_shared<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode>(
node_options);
return node;
}


std::shared_ptr<autoware_auto_perception_msgs::msg::DetectedObject> 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<autoware_auto_perception_msgs::msg::DetectedObject>();
auto ret = std::make_shared<autoware_auto_perception_msgs::msg::DetectedObject>();
ret->kinematics.twist_with_covariance.twist.linear.x = static_cast<double>(twist_x);
ret->kinematics.twist_with_covariance.twist.linear.y = static_cast<double>(twist_y);
ret->kinematics.twist_with_covariance.twist.linear.z = static_cast<double>(twist_z);
Expand All @@ -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));
}
Expand All @@ -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));
}
Expand All @@ -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));
}
Expand All @@ -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));
}
}
}

Check warning on line 208 in perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Large Method

TEST:RadarCrossingObjectsFilter:IsNoise has 156 lines, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

0 comments on commit c22a15d

Please sign in to comment.