From f5d4b6f233445bea0f8157fb4bfab2d92fff6443 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 5 Sep 2022 04:18:41 +0000 Subject: [PATCH] ci(pre-commit): autofix --- .../include/ad_service_state_monitor/state_machine.hpp | 5 ++++- .../src/ad_service_state_monitor_node/main.cpp | 4 ++-- .../src/ad_service_state_monitor_node/state_machine.cpp | 9 +++------ 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/system/ad_service_state_monitor/include/ad_service_state_monitor/state_machine.hpp b/system/ad_service_state_monitor/include/ad_service_state_monitor/state_machine.hpp index 042bc8b2a649f..119e3246e9431 100644 --- a/system/ad_service_state_monitor/include/ad_service_state_monitor/state_machine.hpp +++ b/system/ad_service_state_monitor/include/ad_service_state_monitor/state_machine.hpp @@ -81,7 +81,10 @@ struct Flags class StateMachine { public: - explicit StateMachine(const StateParam & state_param, rclcpp::Logger logger) : state_param_(state_param), logger_(logger) {} + explicit StateMachine(const StateParam & state_param, rclcpp::Logger logger) + : state_param_(state_param), logger_(logger) + { + } AutowareState getCurrentState() const { return autoware_state_; } AutowareState updateState(const StateInput & state_input); diff --git a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/main.cpp b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/main.cpp index dcfdaa88e4965..87d31ac8073cf 100644 --- a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/main.cpp +++ b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/main.cpp @@ -16,10 +16,10 @@ #include -#include - #include +#include + int main(int argc, char * argv[]) { google::InitGoogleLogging(argv[0]); diff --git a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/state_machine.cpp b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/state_machine.cpp index 300282ec014b0..922869af99e56 100644 --- a/system/ad_service_state_monitor/src/ad_service_state_monitor_node/state_machine.cpp +++ b/system/ad_service_state_monitor/src/ad_service_state_monitor_node/state_machine.cpp @@ -54,8 +54,7 @@ bool isStopped( const double th_stopped_velocity_mps) { for (const auto & odometry : odometry_buffer) { - if (!odometry) - { + if (!odometry) { std::cerr << __func__ << ": odometry is nullptr" << std::endl; } if (std::abs(odometry->twist.twist.linear.x) > th_stopped_velocity_mps) { @@ -189,13 +188,11 @@ bool StateMachine::isOverridden() const { return !isEngaged(); } bool StateMachine::hasArrivedGoal() const { - if (!state_input_.current_pose) - { + if (!state_input_.current_pose) { RCLCPP_WARN(logger_, "current_pose is nullptr"); } - if (!state_input_.goal_pose) - { + if (!state_input_.goal_pose) { RCLCPP_WARN(logger_, "goal_pose is nullptr"); }