From 86d30694831bed598bc722fb8e97a27ed4b221f1 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 27 Dec 2023 16:51:15 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../include/reaction_analyzer_node.hpp | 24 +++++++++---------- .../src/reaction_analyzer_node.cpp | 14 +++++------ 2 files changed, 19 insertions(+), 19 deletions(-) diff --git a/tools/reaction_analyzer/include/reaction_analyzer_node.hpp b/tools/reaction_analyzer/include/reaction_analyzer_node.hpp index f8a2eb8aa8f6a..93cd8d00d27c0 100644 --- a/tools/reaction_analyzer/include/reaction_analyzer_node.hpp +++ b/tools/reaction_analyzer/include/reaction_analyzer_node.hpp @@ -55,15 +55,15 @@ using autoware_auto_planning_msgs::msg::Trajectory; using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; -using ControlBuffer = std::pair, std::optional>; +using ControlBuffer = + std::pair, std::optional>; -using BufferVariant = std::variant< - ControlBuffer - // , std::vector // Add other message types here - >; +using BufferVariant = + std::variant // Add other message types here + >; -enum class MessageType -{ +enum class MessageType { Unknown = 0, AckermannControlCommand = 1, }; @@ -118,7 +118,8 @@ class ReactionAnalyzerNode : public rclcpp::Node private: void initObservers(const ChainModules & modules); std::vector subscribers_; - void controlCommandOutputCallback(const std::string & node_name, const AckermannControlCommand::ConstSharedPtr msg_ptr); + void controlCommandOutputCallback( + const std::string & node_name, const AckermannControlCommand::ConstSharedPtr msg_ptr); std::unordered_map messageBuffers_; @@ -164,8 +165,7 @@ class ReactionAnalyzerNode : public rclcpp::Node void onTimer(); void setControlCommandToBuffer( std::vector & buffer, const AckermannControlCommand & cmd); - std::optional findFirstBrakeIdx( - const std::vector & cmd_array); + std::optional findFirstBrakeIdx(const std::vector & cmd_array); // Callbacks void vehiclePoseCallback(const Odometry::ConstSharedPtr msg_ptr); @@ -183,8 +183,8 @@ class ReactionAnalyzerNode : public rclcpp::Node std::optional last_initialize_test_time_; // measurement for control cmd -// std::optional trajectory_follower_brake_cmd; -// std::optional vehicle_cmd_gate_brake_cmd; + // std::optional trajectory_follower_brake_cmd; + // std::optional vehicle_cmd_gate_brake_cmd; // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp index 308088ad68637..b6690448939fa 100644 --- a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp +++ b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp @@ -300,7 +300,7 @@ void ReactionAnalyzerNode::onTimer() all_topics_reacted_ = false; const auto brake_start_idx = findFirstBrakeIdx(message->first); if (brake_start_idx) { -// std::cout << "found brake idx" <(&messageBuffers_[key]); if (tmp) tmp->second = message->first.at(brake_start_idx.value()); @@ -451,7 +451,7 @@ void ReactionAnalyzerNode::controlCommandOutputCallback( ControlBuffer buffer(std::vector{*msg_ptr}, std::nullopt); variant = buffer; } -// std::cout << node_name << std::endl; + // std::cout << node_name << std::endl; setControlCommandToBuffer(std::get(variant).first, *msg_ptr); } @@ -520,17 +520,17 @@ void ReactionAnalyzerNode::setControlCommandToBuffer( itr++; } } -// std::cout << "buffer size: " << buffer.size() << std::endl; + // std::cout << "buffer size: " << buffer.size() << std::endl; buffer.emplace_back(cmd); } std::optional ReactionAnalyzerNode::findFirstBrakeIdx( const std::vector & cmd_array) { -// for (size_t k = 0; k < cmd_array.size(); ++k) { -// std::cout << cmd_array.at(k).longitudinal.acceleration << " "; -// } -// std::cout << std::endl; + // for (size_t k = 0; k < cmd_array.size(); ++k) { + // std::cout << cmd_array.at(k).longitudinal.acceleration << " "; + // } + // std::cout << std::endl; if ( cmd_array.size() < static_cast(node_params_.min_number_descending_order_control_cmd) ||