From 3389459d7223779df9365b677ab32f47d5de3207 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Thu, 13 Jun 2024 14:42:38 +0900 Subject: [PATCH] refactor(pose_estimator_arbiter): apply static analysis (#7473) * refactor based on linter Signed-off-by: a-maumau * style(pre-commit): autofix --------- Signed-off-by: a-maumau Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../rule_helper/grid_key.hpp | 2 +- .../rule_helper/pcd_occupancy.cpp | 5 ++++ .../rule_helper/pcd_occupancy.hpp | 4 +++- .../rule_helper/pose_estimator_area.cpp | 8 +++---- .../rule_helper/pose_estimator_area.hpp | 4 ++-- .../switch_rule/pcd_map_based_rule.cpp | 24 +++++++++++-------- .../switch_rule/pcd_map_based_rule.hpp | 2 +- .../switch_rule/vector_map_based_rule.cpp | 10 +++++--- .../switch_rule/vector_map_based_rule.hpp | 4 ++-- .../test/test_pcd_map_based_rule.cpp | 8 +++---- .../example_rule/test/test_rule_helper.cpp | 12 +++++----- .../test/test_vector_map_based_rule.cpp | 8 +++---- .../pose_estimator_type.hpp | 2 +- .../pose_estimator_arbiter/shared_data.hpp | 22 ++++++++--------- .../stopper/base_stopper.hpp | 10 ++++++-- .../stopper/stopper_artag.hpp | 2 +- .../stopper/stopper_eagleye.hpp | 3 ++- .../stopper/stopper_ndt.hpp | 2 +- .../stopper/stopper_yabloc.hpp | 2 +- .../switch_rule/base_switch_rule.hpp | 6 ++++- .../switch_rule/enable_all_rule.cpp | 7 +++--- .../switch_rule/enable_all_rule.hpp | 6 ++--- 22 files changed, 89 insertions(+), 64 deletions(-) diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/grid_key.hpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/grid_key.hpp index c366a7f02f4fe..b4ad7111e4ba0 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/grid_key.hpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/grid_key.hpp @@ -30,7 +30,7 @@ struct GridKey GridKey() : x(0), y(0) {} GridKey(float x, float y) : x(std::floor(x / unit_length)), y(std::floor(y / unit_length)) {} - pcl::PointXYZ get_center_point() const + [[nodiscard]] pcl::PointXYZ get_center_point() const { pcl::PointXYZ xyz; xyz.x = unit_length * (static_cast(x) + 0.5f); 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 72071b23b467f..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 @@ -20,6 +20,11 @@ #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 e5eb4ff091a31..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 @@ -24,6 +24,8 @@ #include #include +#include + namespace pose_estimator_arbiter::rule_helper { class PcdOccupancy @@ -34,7 +36,7 @@ class PcdOccupancy public: explicit PcdOccupancy(int pcd_density_upper_threshold, int pcd_density_lower_threshold); - MarkerArray debug_marker_array() const; + [[nodiscard]] MarkerArray debug_marker_array() const; void init(PointCloud2::ConstSharedPtr msg); bool ndt_can_operate( const geometry_msgs::msg::Point & position, std::string * optional_message = nullptr) const; 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 4eea34f9ae1ee..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,14 +33,14 @@ using BoostPolygon = boost::geometry::model::polygon; struct PoseEstimatorArea::Impl { - explicit Impl(rclcpp::Logger logger) : logger_(logger) {} + explicit Impl(const rclcpp::Logger & logger) : logger_(logger) {} std::multimap bounding_boxes_; void init(HADMapBin::ConstSharedPtr msg); - bool within( + [[nodiscard]] bool within( const geometry_msgs::msg::Point & point, const std::string & pose_estimator_name) const; - MarkerArray debug_marker_array() const { return marker_array_; } + [[nodiscard]] MarkerArray debug_marker_array() const { return marker_array_; } private: rclcpp::Logger logger_; @@ -105,7 +105,7 @@ void PoseEstimatorArea::Impl::init(HADMapBin::ConstSharedPtr msg) marker.color.set__r(1.0f).set__g(1.0f).set__b(0.0f).set__a(1.0f); marker.ns = subtype; marker.header.frame_id = "map"; - marker.id = marker_array_.markers.size(); + marker.id = static_cast(marker_array_.markers.size()); // Enqueue the vertices of the polygon to bounding box and visualization marker BoostPolygon poly; diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp index 392219b2281e1..74843c66a4eba 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp @@ -40,10 +40,10 @@ class PoseEstimatorArea // This is assumed to be called only once in the vector map callback. void init(const HADMapBin::ConstSharedPtr msg); - bool within( + [[nodiscard]] bool within( const geometry_msgs::msg::Point & point, const std::string & pose_estimator_name) const; - MarkerArray debug_marker_array() const; + [[nodiscard]] MarkerArray debug_marker_array() const; private: struct Impl; 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 4c3829316230b..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 @@ -16,12 +16,16 @@ #include +#include + namespace pose_estimator_arbiter::switch_rule { PcdMapBasedRule::PcdMapBasedRule( - rclcpp::Node & node, const std::unordered_set & running_estimator_list, - const std::shared_ptr shared_data) -: BaseSwitchRule(node), running_estimator_list_(running_estimator_list), shared_data_(shared_data) + rclcpp::Node & node, std::unordered_set running_estimator_list, + std::shared_ptr shared_data) +: BaseSwitchRule(node), + running_estimator_list_(std::move(running_estimator_list)), + shared_data_(std::move(shared_data)) { const int pcd_density_upper_threshold = tier4_autoware_utils::getOrDeclareParameter(node, "pcd_density_upper_threshold"); @@ -63,14 +67,14 @@ std::unordered_map PcdMapBasedRule::update() {PoseEstimatorType::eagleye, false}, {PoseEstimatorType::artag, false}, }; - } else { - debug_string_ = "Enable yabloc: "; - return { - {PoseEstimatorType::ndt, false}, - {PoseEstimatorType::yabloc, true}, - {PoseEstimatorType::eagleye, false}, - {PoseEstimatorType::artag, false}}; } + + debug_string_ = "Enable yabloc: "; + return { + {PoseEstimatorType::ndt, false}, + {PoseEstimatorType::yabloc, true}, + {PoseEstimatorType::eagleye, false}, + {PoseEstimatorType::artag, false}}; } } // namespace pose_estimator_arbiter::switch_rule diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp index 23fd0f812f700..ab4d18dcad66a 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp @@ -31,7 +31,7 @@ class PcdMapBasedRule : public BaseSwitchRule { public: PcdMapBasedRule( - rclcpp::Node & node, const std::unordered_set & running_estimator_list, + rclcpp::Node & node, std::unordered_set running_estimator_list, const std::shared_ptr shared_data); std::unordered_map update() override; 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 675842662acf8..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 @@ -16,12 +16,16 @@ #include +#include + namespace pose_estimator_arbiter::switch_rule { VectorMapBasedRule::VectorMapBasedRule( - rclcpp::Node & node, const std::unordered_set & running_estimator_list, - const std::shared_ptr shared_data) -: BaseSwitchRule(node), running_estimator_list_(running_estimator_list), shared_data_(shared_data) + rclcpp::Node & node, std::unordered_set running_estimator_list, + std::shared_ptr shared_data) +: 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/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp index e3360f9692f86..83723a346054b 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp @@ -32,8 +32,8 @@ class VectorMapBasedRule : public BaseSwitchRule { public: VectorMapBasedRule( - rclcpp::Node & node, const std::unordered_set & running_estimator_list, - const std::shared_ptr shared_data); + rclcpp::Node & node, std::unordered_set running_estimator_list, + std::shared_ptr shared_data); std::unordered_map update() override; diff --git a/localization/pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp b/localization/pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp index 5febfa403363e..f53e01dc9c548 100644 --- a/localization/pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp +++ b/localization/pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp @@ -19,10 +19,10 @@ #include -class MockNode : public ::testing::Test +class PcdMapBasedRuleMockNode : public ::testing::Test { protected: - virtual void SetUp() + void SetUp() override { rclcpp::init(0, nullptr); node = std::make_shared("test_node"); @@ -46,10 +46,10 @@ class MockNode : public ::testing::Test std::shared_ptr shared_data_; std::shared_ptr rule_; - virtual void TearDown() { rclcpp::shutdown(); } + void TearDown() override { rclcpp::shutdown(); } }; -TEST_F(MockNode, pcdMapBasedRule) +TEST_F(PcdMapBasedRuleMockNode, pcdMapBasedRule) { // Create dummy pcd and set { diff --git a/localization/pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp b/localization/pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp index beda4d720b7f6..0001ce674a2e8 100644 --- a/localization/pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp +++ b/localization/pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp @@ -28,10 +28,10 @@ #include -class MockNode : public ::testing::Test +class RuleHelperMockNode : public ::testing::Test { protected: - virtual void SetUp() + void SetUp() override { rclcpp::init(0, nullptr); node = std::make_shared("test_node"); @@ -39,10 +39,10 @@ class MockNode : public ::testing::Test std::shared_ptr node{nullptr}; - virtual void TearDown() { rclcpp::shutdown(); } + void TearDown() override { rclcpp::shutdown(); } }; -TEST_F(MockNode, poseEstimatorArea) +TEST_F(RuleHelperMockNode, poseEstimatorArea) { auto create_polygon3d = []() -> lanelet::Polygon3d { lanelet::Polygon3d polygon; @@ -73,7 +73,7 @@ TEST_F(MockNode, poseEstimatorArea) EXPECT_FALSE(pose_estimator_area.within(Point().set__x(-5).set__y(-5).set__z(0), "yabloc")); } -TEST_F(MockNode, pcdOccupancy) +TEST_F(RuleHelperMockNode, pcdOccupancy) { using pose_estimator_arbiter::rule_helper::PcdOccupancy; const int pcd_density_upper_threshold = 20; @@ -89,7 +89,7 @@ TEST_F(MockNode, pcdOccupancy) EXPECT_FALSE(pcd_occupancy.ndt_can_operate(point, &message)); } -TEST_F(MockNode, gridKey) +TEST_F(RuleHelperMockNode, gridKey) { using pose_estimator_arbiter::rule_helper::GridKey; EXPECT_TRUE(GridKey(10., -5.) == GridKey(10., -10.)); diff --git a/localization/pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp b/localization/pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp index 66d867883272b..a4fd91365f433 100644 --- a/localization/pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp +++ b/localization/pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp @@ -24,10 +24,10 @@ #include -class MockNode : public ::testing::Test +class VectorMapBasedRuleMockNode : public ::testing::Test { protected: - virtual void SetUp() + void SetUp() override { rclcpp::init(0, nullptr); node = std::make_shared("test_node"); @@ -49,10 +49,10 @@ class MockNode : public ::testing::Test std::shared_ptr shared_data_; std::shared_ptr rule_; - virtual void TearDown() { rclcpp::shutdown(); } + void TearDown() override { rclcpp::shutdown(); } }; -TEST_F(MockNode, vectorMapBasedRule) +TEST_F(VectorMapBasedRuleMockNode, vectorMapBasedRule) { // Create dummy lanelet2 and set { diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_type.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_type.hpp index edf12537198a3..d78bfeb05b4f0 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_type.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_type.hpp @@ -18,6 +18,6 @@ namespace pose_estimator_arbiter { enum class PoseEstimatorType : int { ndt = 1, yabloc = 2, eagleye = 4, artag = 8 }; -} +} // namespace pose_estimator_arbiter #endif // POSE_ESTIMATOR_ARBITER__POSE_ESTIMATOR_TYPE_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/shared_data.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/shared_data.hpp index a72dc5585877b..0d3dbfab11cbe 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/shared_data.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/shared_data.hpp @@ -30,29 +30,29 @@ namespace pose_estimator_arbiter template struct CallbackInvokingVariable { - CallbackInvokingVariable() {} + CallbackInvokingVariable() = default; - explicit CallbackInvokingVariable(T initial_data) : value(initial_data) {} + explicit CallbackInvokingVariable(T initial_data) : value_(initial_data) {} // Set data and invoke all callbacks void set_and_invoke(T new_value) { - value = new_value; + value_ = new_value; // Call all callbacks with the new value - for (const auto & callback : callbacks) { - callback(value.value()); + for (const auto & callback : callbacks_) { + callback(value_.value()); } } // Same as std::optional::has_value() - bool has_value() const { return value.has_value(); } + bool has_value() const { return value_.has_value(); } // Same as std::optional::value() - const T operator()() const { return value.value(); } + T operator()() const { return value_.value(); } // Register callback function which is invoked when set_and_invoke() is called - void register_callback(std::function callback) const { callbacks.push_back(callback); } + void register_callback(std::function callback) const { callbacks_.push_back(callback); } // Create subscription callback function which is used as below: // auto subscriber = create_subscription("topic_name", 10, @@ -64,10 +64,10 @@ struct CallbackInvokingVariable private: // The latest data - std::optional value{std::nullopt}; + std::optional value_{std::nullopt}; // These functions are expected not to change the value variable - mutable std::vector> callbacks; + mutable std::vector> callbacks_; }; // This structure is handed to several modules as shared_ptr so that all modules can access data. @@ -80,7 +80,7 @@ struct SharedData using HADMapBin = autoware_map_msgs::msg::LaneletMapBin; using InitializationState = autoware_adapi_v1_msgs::msg::LocalizationInitializationState; - SharedData() {} + SharedData() = default; // Used for stoppers CallbackInvokingVariable eagleye_output_pose_cov; 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 fc2242a0b27e9..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 @@ -20,6 +20,7 @@ #include #include +#include namespace pose_estimator_arbiter::stopper { @@ -28,11 +29,16 @@ class BaseStopper public: using SharedPtr = std::shared_ptr; - explicit BaseStopper(rclcpp::Node * node, const std::shared_ptr shared_data) - : logger_(node->get_logger()), shared_data_(shared_data) + explicit BaseStopper(rclcpp::Node * node, std::shared_ptr shared_data) + : logger_(node->get_logger()), shared_data_(std::move(shared_data)) { } + 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; 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 72a3f5412add0..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,7 +29,7 @@ class StopperArTag : public BaseStopper using SetBool = std_srvs::srv::SetBool; public: - explicit StopperArTag(rclcpp::Node * node, const std::shared_ptr shared_data) + explicit StopperArTag(rclcpp::Node * node, const std::shared_ptr & shared_data) : BaseStopper(node, shared_data) { ar_tag_is_enabled_ = true; 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 12bbe8c9769a1..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,7 +27,8 @@ class StopperEagleye : public BaseStopper using PoseCovStamped = geometry_msgs::msg::PoseWithCovarianceStamped; public: - explicit StopperEagleye(rclcpp::Node * node, const std::shared_ptr shared_data) + explicit StopperEagleye( + rclcpp::Node * node, const std::shared_ptr & shared_data) : BaseStopper(node, shared_data) { eagleye_is_enabled_ = true; diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_ndt.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_ndt.hpp index dacea02f77bde..3b7c083ea31e3 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_ndt.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_ndt.hpp @@ -27,7 +27,7 @@ class StopperNdt : public BaseStopper using PointCloud2 = sensor_msgs::msg::PointCloud2; public: - explicit StopperNdt(rclcpp::Node * node, const std::shared_ptr shared_data) + explicit StopperNdt(rclcpp::Node * node, const std::shared_ptr & shared_data) : BaseStopper(node, shared_data) { ndt_is_enabled_ = true; diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_yabloc.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_yabloc.hpp index 2cd8b66f4ffd4..808a5bf9407ca 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_yabloc.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_yabloc.hpp @@ -29,7 +29,7 @@ class StopperYabLoc : public BaseStopper using SetBool = std_srvs::srv::SetBool; public: - explicit StopperYabLoc(rclcpp::Node * node, const std::shared_ptr shared_data) + explicit StopperYabLoc(rclcpp::Node * node, const std::shared_ptr & shared_data) : BaseStopper(node, shared_data) { yabloc_is_enabled_ = true; 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 5770f18efa32c..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,12 +40,16 @@ 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; virtual std::unordered_map update() = 0; virtual std::string debug_string() { return std::string{}; } virtual MarkerArray debug_marker_array() { return MarkerArray{}; } protected: - rclcpp::Logger get_logger() const { return *logger_ptr_; } + [[nodiscard]] rclcpp::Logger get_logger() const { return *logger_ptr_; } std::shared_ptr logger_ptr_{nullptr}; }; diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp index 2b2e325c3d94b..aebad094a0eca 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp @@ -19,14 +19,15 @@ #include #include #include +#include #include namespace pose_estimator_arbiter::switch_rule { EnableAllRule::EnableAllRule( - rclcpp::Node & node, const std::unordered_set & running_estimator_list, - const std::shared_ptr) -: BaseSwitchRule(node), running_estimator_list_(running_estimator_list) + rclcpp::Node & node, std::unordered_set running_estimator_list, + const std::shared_ptr &) +: BaseSwitchRule(node), running_estimator_list_(std::move(running_estimator_list)) { } diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.hpp index 568226985b2ff..63142b0e662e1 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.hpp @@ -29,10 +29,8 @@ class EnableAllRule : public BaseSwitchRule { public: EnableAllRule( - rclcpp::Node & node, const std::unordered_set & running_estimator_list, - const std::shared_ptr shared_data); - - virtual ~EnableAllRule() = default; + rclcpp::Node & node, std::unordered_set running_estimator_list, + const std::shared_ptr & shared_data); std::unordered_map update() override;