diff --git a/localization/gyro_odometer/src/gyro_odometer_core.cpp b/localization/gyro_odometer/src/gyro_odometer_core.cpp index 81930841311cb..0ec479770740f 100644 --- a/localization/gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/gyro_odometer/src/gyro_odometer_core.cpp @@ -82,8 +82,7 @@ void GyroOdometerNode::callback_vehicle_twist( diagnostics_->clear(); diagnostics_->add_key_value( "topic_time_stamp", - static_cast(vehicle_twist_msg_ptr->header.stamp).nanoseconds() - ); + static_cast(vehicle_twist_msg_ptr->header.stamp).nanoseconds()); vehicle_twist_arrived_ = true; latest_vehicle_twist_ros_time_ = vehicle_twist_msg_ptr->header.stamp; diff --git a/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp b/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp index f72499a28a947..fc331a638a1dd 100644 --- a/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp +++ b/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp @@ -50,12 +50,13 @@ class VelocityGenerator : public rclcpp::Node class GyroOdometerValidator : public rclcpp::Node { public: - GyroOdometerValidator() : Node("gyro_odometer_validator"), - twist_sub(create_subscription("/twist_with_covariance", 1, + GyroOdometerValidator() + : Node("gyro_odometer_validator"), + twist_sub(create_subscription( + "/twist_with_covariance", 1, [this](const TwistWithCovarianceStamped::ConstSharedPtr msg) { received_latest_twist_ptr = msg; - }) - ), + })), received_latest_twist_ptr(nullptr) { } @@ -110,10 +111,8 @@ TEST(GyroOdometer, TestGyroOdometerWithImuAndVelocity) expected_output_twist.twist.twist.angular.y = input_imu.angular_velocity.y; expected_output_twist.twist.twist.angular.z = input_imu.angular_velocity.z; - auto gyro_odometer_node = - std::make_shared( - get_node_options_with_default_params() - ); + auto gyro_odometer_node = std::make_shared( + get_node_options_with_default_params()); auto imu_generator = std::make_shared(); auto velocity_generator = std::make_shared(); auto gyro_odometer_validator_node = std::make_shared(); @@ -140,10 +139,8 @@ TEST(GyroOdometer, TestGyroOdometerImuOnly) { Imu input_imu = generate_sample_imu(); - auto gyro_odometer_node = - std::make_shared( - get_node_options_with_default_params() - ); + auto gyro_odometer_node = std::make_shared( + get_node_options_with_default_params()); auto imu_generator = std::make_shared(); auto gyro_odometer_validator_node = std::make_shared();