From c5ab2842dec0461b8005947feeaf1dd97945f6b0 Mon Sep 17 00:00:00 2001 From: kyoichi-sugahara Date: Tue, 19 Mar 2024 14:13:28 +0900 Subject: [PATCH] move roi_mode_map_ definition inside DualReturnOutlierFilterComponent class Signed-off-by: kyoichi-sugahara --- .../dual_return_outlier_filter_nodelet.hpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 919ddc3b0ea1e..940b24ae30569 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -43,12 +43,6 @@ namespace pointcloud_preprocessor using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; -std::unordered_map roi_mode_map_ = { - {"No_ROI", 0}, - {"Fixed_xyz_ROI", 1}, - {"Fixed_azimuth_ROI", 2}, -}; - class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter { protected: @@ -86,6 +80,12 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter float max_azimuth_deg_; float max_distance_; + std::unordered_map roi_mode_map_ = { + {"No_ROI", 0}, + {"Fixed_xyz_ROI", 1}, + {"Fixed_azimuth_ROI", 2}, + }; + public: PCL_MAKE_ALIGNED_OPERATOR_NEW explicit DualReturnOutlierFilterComponent(const rclcpp::NodeOptions & options);