From 13814246f44a1216dfa38aa9ea58c8a98d3abb4d Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Mon, 22 Jul 2024 15:14:33 +0900 Subject: [PATCH] refactor(imu_corrector): apply static analysis (#7967) * refactor based on linter Signed-off-by: a-maumau * style(pre-commit): autofix --------- Signed-off-by: a-maumau Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yamato Ando --- .../src/gyro_bias_estimation_module.hpp | 2 +- .../imu_corrector/src/imu_corrector_core.cpp | 19 ++++++++++--------- .../imu_corrector/src/imu_corrector_core.hpp | 2 +- .../test/test_gyro_bias_estimation_module.cpp | 4 +++- 4 files changed, 15 insertions(+), 12 deletions(-) diff --git a/sensing/imu_corrector/src/gyro_bias_estimation_module.hpp b/sensing/imu_corrector/src/gyro_bias_estimation_module.hpp index dfa152d32c0d..9eff50d296a9 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimation_module.hpp +++ b/sensing/imu_corrector/src/gyro_bias_estimation_module.hpp @@ -31,7 +31,7 @@ class GyroBiasEstimationModule void update_bias( const std::vector & pose_list, const std::vector & gyro_list); - geometry_msgs::msg::Vector3 get_bias_base_link() const; + [[nodiscard]] geometry_msgs::msg::Vector3 get_bias_base_link() const; private: std::pair gyro_bias_pair_; diff --git a/sensing/imu_corrector/src/imu_corrector_core.cpp b/sensing/imu_corrector/src/imu_corrector_core.cpp index f96bab16443f..c6e12d2481f8 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.cpp +++ b/sensing/imu_corrector/src/imu_corrector_core.cpp @@ -23,7 +23,7 @@ #include -std::array transformCovariance(const std::array & cov) +std::array transform_covariance(const std::array & cov) { using COV_IDX = autoware::universe_utils::xyz_covariance_index::XYZ_COV_IDX; @@ -32,7 +32,7 @@ std::array transformCovariance(const std::array & cov) max_cov = std::max(max_cov, cov[COV_IDX::Y_Y]); max_cov = std::max(max_cov, cov[COV_IDX::Z_Z]); - std::array cov_transformed; + std::array cov_transformed{}; cov_transformed.fill(0.); cov_transformed[COV_IDX::X_X] = max_cov; cov_transformed[COV_IDX::Y_Y] = max_cov; @@ -40,7 +40,7 @@ std::array transformCovariance(const std::array & cov) return cov_transformed; } -geometry_msgs::msg::Vector3 transformVector3( +geometry_msgs::msg::Vector3 transform_vector3( const geometry_msgs::msg::Vector3 & vec, const geometry_msgs::msg::TransformStamped & transform) { geometry_msgs::msg::Vector3Stamped vec_stamped; @@ -73,12 +73,12 @@ ImuCorrector::ImuCorrector(const rclcpp::NodeOptions & options) accel_stddev_imu_link_ = declare_parameter("acceleration_stddev", 10000.0); imu_sub_ = create_subscription( - "input", rclcpp::QoS{1}, std::bind(&ImuCorrector::callbackImu, this, std::placeholders::_1)); + "input", rclcpp::QoS{1}, std::bind(&ImuCorrector::callback_imu, this, std::placeholders::_1)); imu_pub_ = create_publisher("output", rclcpp::QoS{10}); } -void ImuCorrector::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr) +void ImuCorrector::callback_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr) { sensor_msgs::msg::Imu imu_msg; imu_msg = *imu_msg_ptr; @@ -113,12 +113,13 @@ void ImuCorrector::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_m imu_msg_base_link.header.stamp = imu_msg_ptr->header.stamp; imu_msg_base_link.header.frame_id = output_frame_; imu_msg_base_link.linear_acceleration = - transformVector3(imu_msg.linear_acceleration, *tf_imu2base_ptr); + transform_vector3(imu_msg.linear_acceleration, *tf_imu2base_ptr); imu_msg_base_link.linear_acceleration_covariance = - transformCovariance(imu_msg.linear_acceleration_covariance); - imu_msg_base_link.angular_velocity = transformVector3(imu_msg.angular_velocity, *tf_imu2base_ptr); + transform_covariance(imu_msg.linear_acceleration_covariance); + imu_msg_base_link.angular_velocity = + transform_vector3(imu_msg.angular_velocity, *tf_imu2base_ptr); imu_msg_base_link.angular_velocity_covariance = - transformCovariance(imu_msg.angular_velocity_covariance); + transform_covariance(imu_msg.angular_velocity_covariance); imu_pub_->publish(imu_msg_base_link); } diff --git a/sensing/imu_corrector/src/imu_corrector_core.hpp b/sensing/imu_corrector/src/imu_corrector_core.hpp index 0dacab465147..c02aa88a313a 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.hpp +++ b/sensing/imu_corrector/src/imu_corrector_core.hpp @@ -37,7 +37,7 @@ class ImuCorrector : public rclcpp::Node explicit ImuCorrector(const rclcpp::NodeOptions & options); private: - void callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr); + void callback_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr); rclcpp::Subscription::SharedPtr imu_sub_; diff --git a/sensing/imu_corrector/test/test_gyro_bias_estimation_module.cpp b/sensing/imu_corrector/test/test_gyro_bias_estimation_module.cpp index 78558feeb793..257552e15cba 100644 --- a/sensing/imu_corrector/test/test_gyro_bias_estimation_module.cpp +++ b/sensing/imu_corrector/test/test_gyro_bias_estimation_module.cpp @@ -63,7 +63,9 @@ TEST_F(GyroBiasEstimationModuleTest, GetBiasEstimationWhenVehicleStopped) TEST_F(GyroBiasEstimationModuleTest, GetInsufficientDataException) { - ASSERT_THROW(module.get_bias_base_link(), std::runtime_error); + // for the case of method with [[nodiscard]] attribute + geometry_msgs::msg::Vector3 bias_base_link; + ASSERT_THROW(bias_base_link = module.get_bias_base_link(), std::runtime_error); } TEST_F(GyroBiasEstimationModuleTest, GetInsufficientDataExceptionWhenVehicleMoving)