From aa614ae44581e0c3232d396f54b0d9907c04f496 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 6 Jun 2024 11:31:53 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../pose_instability_detector.hpp | 7 ++++--- .../src/pose_instability_detector.cpp | 8 +++++--- 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/localization/pose_instability_detector/include/autoware/pose_instability_detector/pose_instability_detector.hpp b/localization/pose_instability_detector/include/autoware/pose_instability_detector/pose_instability_detector.hpp index 3795fe82dca71..0a55a5005dde1 100644 --- a/localization/pose_instability_detector/include/autoware/pose_instability_detector/pose_instability_detector.hpp +++ b/localization/pose_instability_detector/include/autoware/pose_instability_detector/pose_instability_detector.hpp @@ -23,8 +23,8 @@ #include <nav_msgs/msg/odometry.hpp> #include <deque> -#include <vector> #include <tuple> +#include <vector> class PoseInstabilityDetector : public rclcpp::Node { @@ -39,7 +39,8 @@ class PoseInstabilityDetector : public rclcpp::Node using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; public: - struct ThresholdValues { + struct ThresholdValues + { double position_x; double position_y; double position_z; @@ -47,7 +48,7 @@ class PoseInstabilityDetector : public rclcpp::Node double angle_y; double angle_z; }; - + explicit PoseInstabilityDetector(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); ThresholdValues calculate_threshold(double interval_sec); void dead_reckon( diff --git a/localization/pose_instability_detector/src/pose_instability_detector.cpp b/localization/pose_instability_detector/src/pose_instability_detector.cpp index 1475ece8ac3ea..fa7b2ecf16562 100644 --- a/localization/pose_instability_detector/src/pose_instability_detector.cpp +++ b/localization/pose_instability_detector/src/pose_instability_detector.cpp @@ -136,7 +136,8 @@ void PoseInstabilityDetector::callback_timer() diff_pose_pub_->publish(diff_pose); // publish diagnostics - ThresholdValues threshold_values = calculate_threshold((latest_odometry_time - prev_odometry_time).seconds()); + ThresholdValues threshold_values = + calculate_threshold((latest_odometry_time - prev_odometry_time).seconds()); const std::vector<double> thresholds = {threshold_values.position_x, threshold_values.position_y, threshold_values.position_z, threshold_values.angle_x, @@ -176,7 +177,8 @@ void PoseInstabilityDetector::callback_timer() prev_odometry_ = latest_odometry_; } -PoseInstabilityDetector::ThresholdValues PoseInstabilityDetector::calculate_threshold(double interval_sec) +PoseInstabilityDetector::ThresholdValues PoseInstabilityDetector::calculate_threshold( + double interval_sec) { // Calculate maximum longitudinal difference const double longitudinal_difference = @@ -323,7 +325,7 @@ PoseInstabilityDetector::clip_out_necessary_twist( // get iterator to the element that is right before start_time (if it does not exist, start_it = // twist_buffer.begin()) auto start_it = twist_buffer.begin(); - + for (auto it = twist_buffer.begin(); it != twist_buffer.end(); ++it) { if (rclcpp::Time(it->header.stamp) > start_time) { break;