From 2e6a3ed342776ada47ebde951e2a000e3efbc5b7 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 13 Jun 2024 02:40:12 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp | 8 ++++---- .../pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp | 4 ++-- .../rule_helper/pose_estimator_area.cpp | 2 +- .../switch_rule/pcd_map_based_rule.cpp | 3 ++- .../switch_rule/vector_map_based_rule.cpp | 3 ++- .../src/pose_estimator_arbiter/stopper/base_stopper.hpp | 8 ++++---- .../src/pose_estimator_arbiter/stopper/stopper_artag.hpp | 4 ++-- .../pose_estimator_arbiter/stopper/stopper_eagleye.hpp | 5 +++-- .../switch_rule/base_switch_rule.hpp | 8 ++++---- 9 files changed, 24 insertions(+), 21 deletions(-) diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp index dd68952b85100..4b0188a1638f6 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp @@ -16,15 +16,15 @@ #include "pose_estimator_arbiter/rule_helper/grid_key.hpp" +#include + +#include + #include #include #include #include -#include - -#include - namespace pose_estimator_arbiter::rule_helper { PcdOccupancy::PcdOccupancy(int pcd_density_upper_threshold, int pcd_density_lower_threshold) diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp index 0814fa6c6bf26..098704e11aba9 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp @@ -15,8 +15,6 @@ #ifndef POSE_ESTIMATOR_ARBITER__RULE_HELPER__PCD_OCCUPANCY_HPP_ #define POSE_ESTIMATOR_ARBITER__RULE_HELPER__PCD_OCCUPANCY_HPP_ -#include - #include #include @@ -26,6 +24,8 @@ #include #include +#include + namespace pose_estimator_arbiter::rule_helper { class PcdOccupancy diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp index b333063cda716..df7f9c6c1035f 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp @@ -33,7 +33,7 @@ using BoostPolygon = boost::geometry::model::polygon; struct PoseEstimatorArea::Impl { - explicit Impl(const rclcpp::Logger& logger) : logger_(logger) {} + explicit Impl(const rclcpp::Logger & logger) : logger_(logger) {} std::multimap bounding_boxes_; void init(HADMapBin::ConstSharedPtr msg); diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp index d3269e167ce2c..0d8880d5c4d16 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp @@ -23,7 +23,8 @@ namespace pose_estimator_arbiter::switch_rule PcdMapBasedRule::PcdMapBasedRule( rclcpp::Node & node, std::unordered_set running_estimator_list, std::shared_ptr shared_data) -: BaseSwitchRule(node), running_estimator_list_(std::move(running_estimator_list)), +: BaseSwitchRule(node), + running_estimator_list_(std::move(running_estimator_list)), shared_data_(std::move(shared_data)) { const int pcd_density_upper_threshold = diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.cpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.cpp index 6338304ea6992..dffb738e87685 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.cpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.cpp @@ -23,7 +23,8 @@ namespace pose_estimator_arbiter::switch_rule VectorMapBasedRule::VectorMapBasedRule( rclcpp::Node & node, std::unordered_set running_estimator_list, std::shared_ptr shared_data) -: BaseSwitchRule(node), running_estimator_list_(std::move(running_estimator_list)), +: BaseSwitchRule(node), + running_estimator_list_(std::move(running_estimator_list)), shared_data_(std::move(shared_data)) { pose_estimator_area_ = std::make_unique(node.get_logger()); diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/base_stopper.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/base_stopper.hpp index 79c50615abb42..d64592a12308e 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/base_stopper.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/base_stopper.hpp @@ -35,10 +35,10 @@ class BaseStopper } virtual ~BaseStopper() = default; - BaseStopper(const BaseStopper& other) = default; - BaseStopper(BaseStopper&& other) noexcept = default; - BaseStopper& operator=(const BaseStopper& other) = default; - BaseStopper& operator=(BaseStopper&& other) noexcept = default; + BaseStopper(const BaseStopper & other) = default; + BaseStopper(BaseStopper && other) noexcept = default; + BaseStopper & operator=(const BaseStopper & other) = default; + BaseStopper & operator=(BaseStopper && other) noexcept = default; void enable() { set_enable(true); } void disable() { set_enable(false); } diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_artag.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_artag.hpp index 8f5fea80fd0c0..f334983f33aad 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_artag.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_artag.hpp @@ -29,8 +29,8 @@ class StopperArTag : public BaseStopper using SetBool = std_srvs::srv::SetBool; public: - explicit StopperArTag(rclcpp::Node * node, - const std::shared_ptr & shared_data) : BaseStopper(node, shared_data) + explicit StopperArTag(rclcpp::Node * node, const std::shared_ptr & shared_data) + : BaseStopper(node, shared_data) { ar_tag_is_enabled_ = true; pub_image_ = node->create_publisher("~/output/artag/image", rclcpp::SensorDataQoS()); diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_eagleye.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_eagleye.hpp index 46db58209662f..cc800ad6bdee4 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_eagleye.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_eagleye.hpp @@ -27,8 +27,9 @@ class StopperEagleye : public BaseStopper using PoseCovStamped = geometry_msgs::msg::PoseWithCovarianceStamped; public: - explicit StopperEagleye(rclcpp::Node * node, - const std::shared_ptr & shared_data) : BaseStopper(node, shared_data) + explicit StopperEagleye( + rclcpp::Node * node, const std::shared_ptr & shared_data) + : BaseStopper(node, shared_data) { eagleye_is_enabled_ = true; pub_pose_ = node->create_publisher("~/output/eagleye/pose_with_covariance", 5); diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/base_switch_rule.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/base_switch_rule.hpp index 49f80c501a412..95d10c2b741a8 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/base_switch_rule.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/base_switch_rule.hpp @@ -40,10 +40,10 @@ class BaseSwitchRule } virtual ~BaseSwitchRule() = default; - BaseSwitchRule(const BaseSwitchRule& other) = default; - BaseSwitchRule(BaseSwitchRule&& other) noexcept = default; - BaseSwitchRule& operator=(const BaseSwitchRule& other) = default; - BaseSwitchRule& operator=(BaseSwitchRule&& other) noexcept = default; + BaseSwitchRule(const BaseSwitchRule & other) = default; + BaseSwitchRule(BaseSwitchRule && other) noexcept = default; + BaseSwitchRule & operator=(const BaseSwitchRule & other) = default; + BaseSwitchRule & operator=(BaseSwitchRule && other) noexcept = default; virtual std::unordered_map update() = 0; virtual std::string debug_string() { return std::string{}; } virtual MarkerArray debug_marker_array() { return MarkerArray{}; }