Skip to content

Commit

Permalink
chore: fix test naming error
Browse files Browse the repository at this point in the history
Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf committed Sep 19, 2024
1 parent 896d843 commit 3027ec1
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 26 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -66,12 +66,13 @@ class DistortionCorrectorBase
bool pointcloud_transform_needed_{false};
bool pointcloud_transform_exists_{false};
bool imu_transform_exists_{false};
rclcpp::Node * node_;
std::unique_ptr<autoware::universe_utils::ManagedTransformBuffer> managed_tf_buffer_{nullptr};

std::deque<geometry_msgs::msg::TwistStamped> twist_queue_;
std::deque<geometry_msgs::msg::Vector3Stamped> angular_velocity_queue_;

rclcpp::Node * node_;

void get_imu_transformation(const std::string & base_frame, const std::string & imu_frame);
void enqueue_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg);
void get_twist_and_imu_iterator(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -348,7 +348,7 @@ class DistortionCorrectorTest : public ::testing::Test
bool debug_{false};
};

TEST_F(DistortionCorrectorTest, Testprocess_twist_message)
TEST_F(DistortionCorrectorTest, TestProcessTwistMessage)
{
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
auto twist_msg = generateTwistMsg(twist_linear_x_, twist_angular_z_, timestamp);
Expand All @@ -359,7 +359,7 @@ TEST_F(DistortionCorrectorTest, Testprocess_twist_message)
EXPECT_EQ(distortion_corrector_2d_->get_twist_queue().front().twist.angular.z, twist_angular_z_);
}

TEST_F(DistortionCorrectorTest, Testprocess_imu_message)
TEST_F(DistortionCorrectorTest, TestProcessImuMessage)
{
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
auto imu_msg = generateImuMsg(imu_angular_x_, imu_angular_y_, imu_angular_z_, timestamp);
Expand All @@ -371,7 +371,7 @@ TEST_F(DistortionCorrectorTest, Testprocess_imu_message)
standard_tolerance_);
}

TEST_F(DistortionCorrectorTest, Testis_pointcloud_valid)
TEST_F(DistortionCorrectorTest, TestIsPointcloudValid)
{
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);

Expand All @@ -387,28 +387,28 @@ TEST_F(DistortionCorrectorTest, Testis_pointcloud_valid)
EXPECT_FALSE(result);
}

TEST_F(DistortionCorrectorTest, Testset_pointcloud_transformWithBaseLink)
TEST_F(DistortionCorrectorTest, TestSetPointcloudTransformWithBaseLink)
{
distortion_corrector_2d_->set_pointcloud_transform("base_link", "base_link");
EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists());
EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed());
}

TEST_F(DistortionCorrectorTest, Testset_pointcloud_transformWithLidarFrame)
TEST_F(DistortionCorrectorTest, TestSetPointcloudTransformWithLidarFrame)
{
distortion_corrector_2d_->set_pointcloud_transform("base_link", "lidar_top");
EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists());
EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_needed());
}

TEST_F(DistortionCorrectorTest, Testset_pointcloud_transformWithMissingFrame)
TEST_F(DistortionCorrectorTest, TestSetPointcloudTransformWithMissingFrame)
{
distortion_corrector_2d_->set_pointcloud_transform("base_link", "missing_lidar_frame");
EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_exists());
EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed());
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloudWithEmptyTwist)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloudWithEmptyTwist)
{
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
// Generate the point cloud message
Expand Down Expand Up @@ -448,7 +448,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloudWithEmptyTwist)
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloudWithEmptyPointCloud)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloudWithEmptyPointCloud)
{
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
// Generate and process multiple twist messages
Expand All @@ -465,7 +465,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloudWithEmptyPointCloud)
EXPECT_EQ(empty_pointcloud.row_step, 0);
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloud2dWithoutImuInBaseLink)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloud2dWithoutImuInBaseLink)
{
// Generate the point cloud message
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand Down Expand Up @@ -510,7 +510,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloud2dWithoutImuInBaseLink)
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloud2dWithImuInBaseLink)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloud2dWithImuInBaseLink)
{
// Generate the point cloud message
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand Down Expand Up @@ -557,7 +557,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloud2dWithImuInBaseLink)
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloud2dWithImuInLidarFrame)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloud2dWithImuInLidarFrame)
{
// Generate the point cloud message
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand Down Expand Up @@ -607,7 +607,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloud2dWithImuInLidarFrame)
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloud3dWithoutImuInBaseLink)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloud3dWithoutImuInBaseLink)
{
// Generate the point cloud message
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand Down Expand Up @@ -652,7 +652,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloud3dWithoutImuInBaseLink)
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloud3dWithImuInBaseLink)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloud3dWithImuInBaseLink)
{
// Generate the point cloud message
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand Down Expand Up @@ -702,7 +702,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloud3dWithImuInBaseLink)
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloud3dWithImuInLidarFrame)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloud3dWithImuInLidarFrame)
{
// Generate the point cloud message
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand Down Expand Up @@ -751,7 +751,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloud3dWithImuInLidarFrame)
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloudWithPureLinearMotion)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloudWithPureLinearMotion)
{
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
auto [default_points, default_azimuths] =
Expand Down Expand Up @@ -842,7 +842,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloudWithPureLinearMotion)
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloudWithPureRotationalMotion)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloudWithPureRotationalMotion)
{
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
auto [default_points, default_azimuths] =
Expand Down Expand Up @@ -946,7 +946,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloudWithPureRotationalMotion
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloudNotUpdatingAzimuthAndDistance)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloudNotUpdatingAzimuthAndDistance)
{
// Test the case when the cloud will not update the azimuth and distance values
// 1. when pointcloud is in base_link (pointcloud_transform_needed() is false)
Expand Down Expand Up @@ -1059,7 +1059,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloudNotUpdatingAzimuthAndDis
}
}

Check warning on line 1060 in sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Large Method

TEST:DistortionCorrectorTest:TestUndistortPointcloudNotUpdatingAzimuthAndDistance has 76 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.

TEST_F(DistortionCorrectorTest, Testundistort_pointcloudUpdateAzimuthAndDistanceInVelodyne)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloudUpdateAzimuthAndDistanceInVelodyne)
{
// Generate the point cloud message in sensor frame
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand Down Expand Up @@ -1118,7 +1118,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloudUpdateAzimuthAndDistance
}
}

TEST_F(DistortionCorrectorTest, Testundistort_pointcloudUpdateAzimuthAndDistanceInHesai)
TEST_F(DistortionCorrectorTest, TestUndistortPointcloudUpdateAzimuthAndDistanceInHesai)
{
// Generate the point cloud message in sensor frame
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand Down Expand Up @@ -1177,7 +1177,7 @@ TEST_F(DistortionCorrectorTest, Testundistort_pointcloudUpdateAzimuthAndDistance
}
}

TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnEmptyPointcloud)
TEST_F(DistortionCorrectorTest, TestTryComputeAngleConversionOnEmptyPointcloud)
{
// test empty pointcloud
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand All @@ -1189,7 +1189,7 @@ TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnEmptyPointclou
EXPECT_FALSE(angle_conversion_opt.has_value());
}

TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnVelodynePointcloud)
TEST_F(DistortionCorrectorTest, TestTryComputeAngleConversionOnVelodynePointcloud)
{
// test velodyne pointcloud (x-axis: 0 degree, y-axis: 270 degree)
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand All @@ -1212,7 +1212,7 @@ TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnVelodynePointc
EXPECT_NEAR(angle_conversion_opt->offset_rad, 0, standard_tolerance_);
}

TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnHesaiPointcloud)
TEST_F(DistortionCorrectorTest, TestTryComputeAngleConversionOnHesaiPointcloud)
{
// test hesai pointcloud (x-axis: 90 degree, y-axis: 0 degree)
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand All @@ -1235,7 +1235,7 @@ TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnHesaiPointclou
angle_conversion_opt->offset_rad, autoware::universe_utils::pi / 2, standard_tolerance_);
}

TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionCartesianPointcloud)
TEST_F(DistortionCorrectorTest, TestTryComputeAngleConversionCartesianPointcloud)
{
// test pointcloud that use cartesian coordinate for azimuth (x-axis: 0 degree, y-axis: 90 degree)
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand All @@ -1260,7 +1260,7 @@ TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionCartesianPointcl
EXPECT_NEAR(angle_conversion_opt->offset_rad, 0, standard_tolerance_);
}

TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnRandomPointcloud)
TEST_F(DistortionCorrectorTest, TestTryComputeAngleConversionOnRandomPointcloud)
{
// test pointcloud that use coordinate (x-axis: 270 degree, y-axis: 0 degree)
rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME);
Expand All @@ -1284,7 +1284,7 @@ TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnRandomPointclo
angle_conversion_opt->offset_rad, autoware::universe_utils::pi * 3 / 2, standard_tolerance_);
}

TEST_F(DistortionCorrectorTest, Testtry_compute_angle_conversionOnBadAzimuthPointcloud)
TEST_F(DistortionCorrectorTest, TestTryComputeAngleConversionOnBadAzimuthPointcloud)
{
// test pointcloud that can cause the angle conversion to fail.
// 1. angle difference is 0
Expand Down

0 comments on commit 3027ec1

Please sign in to comment.