diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 30b5982d0dd25..b796a84f48be6 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -206,7 +206,7 @@ sensing/image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp sensing/image_transport_decompressor/** kenzo.lobos@tier4.jp yukihiro.saito@tier4.jp sensing/imu_corrector/** taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp -sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp david.wong@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp melike@leodrive.ai shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +sensing/autoware_pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp david.wong@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp melike@leodrive.ai shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp diff --git a/control/autoware_autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml index 0c64b9498486a..d0c75f893cd2d 100644 --- a/control/autoware_autonomous_emergency_braking/package.xml +++ b/control/autoware_autonomous_emergency_braking/package.xml @@ -18,6 +18,7 @@ autoware_control_msgs autoware_motion_utils autoware_planning_msgs + autoware_pointcloud_preprocessor autoware_system_msgs autoware_universe_utils autoware_vehicle_info_utils @@ -27,7 +28,6 @@ nav_msgs pcl_conversions pcl_ros - pointcloud_preprocessor rclcpp rclcpp_components sensor_msgs diff --git a/launch/tier4_localization_launch/launch/util/util.launch.xml b/launch/tier4_localization_launch/launch/util/util.launch.xml index 63dac42f2063e..7040430d5d1ac 100644 --- a/launch/tier4_localization_launch/launch/util/util.launch.xml +++ b/launch/tier4_localization_launch/launch/util/util.launch.xml @@ -9,21 +9,21 @@ - + - + - + diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index b6f3ad4c27eea..b3dc75bbf79cc 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -19,6 +19,7 @@ automatic_pose_initializer autoware_ar_tag_based_localizer + autoware_pointcloud_preprocessor eagleye_geo_pose_fusion eagleye_gnss_converter eagleye_rt @@ -26,7 +27,6 @@ geo_pose_projector gyro_odometer ndt_scan_matcher - pointcloud_preprocessor pose_estimator_arbiter pose_initializer pose_instability_detector diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/filter/pointcloud_map_filter.launch.py b/launch/tier4_perception_launch/launch/object_recognition/detection/filter/pointcloud_map_filter.launch.py index 6c0e5f20b8957..43762578aa552 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/filter/pointcloud_map_filter.launch.py +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/filter/pointcloud_map_filter.launch.py @@ -56,8 +56,8 @@ def create_no_compare_map_pipeline(self): components = [] components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::ApproximateDownsampleFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::ApproximateDownsampleFilterComponent", name="voxel_grid_downsample_filter", remappings=[ ("input", LaunchConfiguration("input_topic")), @@ -84,8 +84,8 @@ def create_compare_map_pipeline(self): ) components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", name="voxel_grid_downsample_filter", remappings=[ ("input", LaunchConfiguration("input_topic")), diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index fd38b7bfd6ab3..622374a4edc37 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -91,8 +91,8 @@ def create_additional_pipeline(self, lidar_name): components = [] components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name=f"{lidar_name}_crop_box_filter", remappings=[ ("input", f"/sensing/lidar/{lidar_name}/pointcloud"), @@ -137,8 +137,8 @@ def create_ransac_pipeline(self): components = [] components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", name="concatenate_data", namespace="plane_fitting", remappings=[ @@ -161,8 +161,8 @@ def create_ransac_pipeline(self): components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="short_height_obstacle_detection_area_filter", namespace="plane_fitting", remappings=[ @@ -186,8 +186,8 @@ def create_ransac_pipeline(self): components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::Lanelet2MapFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::Lanelet2MapFilterComponent", name="vector_map_filter", namespace="plane_fitting", remappings=[ @@ -243,8 +243,8 @@ def create_common_pipeline(self, input_topic, output_topic): components = [] components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter", remappings=[ ("input", input_topic), @@ -416,8 +416,8 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic, con components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", name="voxel_grid_filter", namespace="elevation_map", remappings=[ @@ -441,8 +441,8 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic, con components.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::VoxelGridOutlierFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::VoxelGridOutlierFilterComponent", name="voxel_grid_outlier_filter", namespace="elevation_map", remappings=[ @@ -468,8 +468,8 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic, con @staticmethod def get_additional_lidars_concatenated_component(input_topics, output_topic): return ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", name="concatenate_data", remappings=[ ("~/input/odom", "/localization/kinematic_state"), @@ -488,8 +488,8 @@ def get_additional_lidars_concatenated_component(input_topics, output_topic): @staticmethod def get_single_frame_obstacle_segmentation_concatenated_component(input_topics, output_topic): return ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", name="concatenate_no_ground_data", remappings=[ ("~/input/odom", "/localization/kinematic_state"), diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 6c428a5adea0b..71c7544f4dd94 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -144,7 +144,12 @@ - + diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 340ac7448b96d..67394cb4526a9 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -22,6 +22,7 @@ autoware_object_merger autoware_object_range_splitter autoware_object_velocity_splitter + autoware_pointcloud_preprocessor autoware_radar_crossing_objects_noise_filter autoware_radar_fusion_to_detected_object autoware_radar_object_clustering @@ -37,7 +38,6 @@ image_transport_decompressor lidar_apollo_instance_segmentation occupancy_grid_map_outlier_filter - pointcloud_preprocessor pointcloud_to_laserscan probabilistic_occupancy_grid_map shape_estimation diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 3c58c8d85b5be..7a8e779fd4032 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -277,7 +277,7 @@ - + diff --git a/perception/autoware_euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/autoware_euclidean_cluster/launch/euclidean_cluster.launch.py index 9420abe214ecc..fbbd70b966809 100644 --- a/perception/autoware_euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/autoware_euclidean_cluster/launch/euclidean_cluster.launch.py @@ -36,9 +36,9 @@ def load_composable_node_param(param_path): pkg = "autoware_euclidean_cluster" low_height_cropbox_filter_component = ComposableNode( - package="pointcloud_preprocessor", + package="autoware_pointcloud_preprocessor", namespace=ns, - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="low_height_crop_box_filter", remappings=[ ("input", LaunchConfiguration("input_pointcloud")), diff --git a/perception/autoware_euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py b/perception/autoware_euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py index cbc2401ede5b7..6a678cc4c7f59 100644 --- a/perception/autoware_euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py +++ b/perception/autoware_euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py @@ -35,9 +35,9 @@ def load_composable_node_param(param_path): pkg = "autoware_euclidean_cluster" low_height_cropbox_filter_component = ComposableNode( - package="pointcloud_preprocessor", + package="autoware_pointcloud_preprocessor", namespace=ns, - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="low_height_crop_box_filter", remappings=[ ("input", LaunchConfiguration("input_pointcloud")), diff --git a/perception/compare_map_segmentation/CMakeLists.txt b/perception/compare_map_segmentation/CMakeLists.txt index 0a33711e946ef..6d0aeb3c7df6b 100644 --- a/perception/compare_map_segmentation/CMakeLists.txt +++ b/perception/compare_map_segmentation/CMakeLists.txt @@ -31,7 +31,7 @@ add_library(${PROJECT_NAME} SHARED ) target_link_libraries(${PROJECT_NAME} - pointcloud_preprocessor::pointcloud_preprocessor_filter_base + autoware_pointcloud_preprocessor::pointcloud_preprocessor_filter_base ${Boost_LIBRARIES} ${OpenCV_LIBRARIES} ${PCL_LIBRARIES} diff --git a/perception/compare_map_segmentation/package.xml b/perception/compare_map_segmentation/package.xml index 7403dc0713475..b701fdaa23b76 100644 --- a/perception/compare_map_segmentation/package.xml +++ b/perception/compare_map_segmentation/package.xml @@ -18,12 +18,12 @@ autoware_cmake autoware_map_msgs + autoware_pointcloud_preprocessor autoware_universe_utils grid_map_pcl grid_map_ros nav_msgs pcl_conversions - pointcloud_preprocessor rclcpp rclcpp_components sensor_msgs diff --git a/perception/compare_map_segmentation/src/compare_elevation_map_filter/node.hpp b/perception/compare_map_segmentation/src/compare_elevation_map_filter/node.hpp index ba2328d862951..ceddaa67ac2cd 100644 --- a/perception/compare_map_segmentation/src/compare_elevation_map_filter/node.hpp +++ b/perception/compare_map_segmentation/src/compare_elevation_map_filter/node.hpp @@ -15,7 +15,7 @@ #ifndef COMPARE_ELEVATION_MAP_FILTER__NODE_HPP_ #define COMPARE_ELEVATION_MAP_FILTER__NODE_HPP_ -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include @@ -31,7 +31,7 @@ #include namespace autoware::compare_map_segmentation { -class CompareElevationMapFilterComponent : public pointcloud_preprocessor::Filter +class CompareElevationMapFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: void filter( diff --git a/perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp b/perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp index 115a73cf0d263..d0cb5b3c62992 100644 --- a/perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp +++ b/perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp @@ -16,7 +16,7 @@ #define DISTANCE_BASED_COMPARE_MAP_FILTER__NODE_HPP_ #include "../voxel_grid_map_loader/voxel_grid_map_loader.hpp" -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include // for pcl::isFinite #include @@ -100,7 +100,7 @@ class DistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader } }; -class DistanceBasedCompareMapFilterComponent : public pointcloud_preprocessor::Filter +class DistanceBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( diff --git a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp index 26b0204210209..0466d20403ca3 100644 --- a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp +++ b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp @@ -16,7 +16,7 @@ #define VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT #include "../voxel_grid_map_loader/voxel_grid_map_loader.hpp" -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include @@ -56,7 +56,8 @@ class VoxelBasedApproximateDynamicMapLoader : public VoxelGridDynamicMapLoader bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) override; }; -class VoxelBasedApproximateCompareMapFilterComponent : public pointcloud_preprocessor::Filter +class VoxelBasedApproximateCompareMapFilterComponent +: public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( diff --git a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp index 1861a710cdebd..a3eb866d77e31 100644 --- a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp @@ -26,7 +26,7 @@ namespace autoware::compare_map_segmentation { -using pointcloud_preprocessor::get_param; +using autoware::pointcloud_preprocessor::get_param; VoxelBasedCompareMapFilterComponent::VoxelBasedCompareMapFilterComponent( const rclcpp::NodeOptions & options) diff --git a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp index 6e03e5d7a2e09..ac81eae85b8a0 100644 --- a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp +++ b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp @@ -16,7 +16,7 @@ #define VOXEL_BASED_COMPARE_MAP_FILTER__NODE_HPP_ #include "../voxel_grid_map_loader/voxel_grid_map_loader.hpp" -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include @@ -26,7 +26,7 @@ namespace autoware::compare_map_segmentation { -class VoxelBasedCompareMapFilterComponent : public pointcloud_preprocessor::Filter +class VoxelBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( diff --git a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp index e0656359f3df2..15ed2a32ff213 100644 --- a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp +++ b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp @@ -16,7 +16,7 @@ #define VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT #include "../voxel_grid_map_loader/voxel_grid_map_loader.hpp" -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include @@ -123,7 +123,7 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader } }; -class VoxelDistanceBasedCompareMapFilterComponent : public pointcloud_preprocessor::Filter +class VoxelDistanceBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( diff --git a/perception/ground_segmentation/README.md b/perception/ground_segmentation/README.md index ec52e33e6db0a..8eec3a8ee308c 100644 --- a/perception/ground_segmentation/README.md +++ b/perception/ground_segmentation/README.md @@ -44,7 +44,7 @@ Detail description of each ground segmentation algorithm is in the following lin ## Assumptions / Known limits -`pointcloud_preprocessor::Filter` is implemented based on pcl_perception [1] because of [this issue](https://github.com/ros-perception/perception_pcl/issues/9). +`autoware::pointcloud_preprocessor::Filter` is implemented based on pcl_perception [1] because of [this issue](https://github.com/ros-perception/perception_pcl/issues/9). ## References/External links diff --git a/perception/ground_segmentation/docs/ransac-ground-filter.md b/perception/ground_segmentation/docs/ransac-ground-filter.md index 8bec24ea34d0c..a11a35521d173 100644 --- a/perception/ground_segmentation/docs/ransac-ground-filter.md +++ b/perception/ground_segmentation/docs/ransac-ground-filter.md @@ -10,13 +10,13 @@ Apply the input points to the plane, and set the points at a certain distance fr ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ## Parameters ### Node Parameters -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). #### Core Parameters diff --git a/perception/ground_segmentation/docs/ray-ground-filter.md b/perception/ground_segmentation/docs/ray-ground-filter.md index 4774939a6a367..9b80b0588f851 100644 --- a/perception/ground_segmentation/docs/ray-ground-filter.md +++ b/perception/ground_segmentation/docs/ray-ground-filter.md @@ -12,13 +12,13 @@ The points is separated radially (Ray), and the ground is classified for each Ra ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ## Parameters ### Node Parameters -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Core Parameters diff --git a/perception/ground_segmentation/docs/scan-ground-filter.md b/perception/ground_segmentation/docs/scan-ground-filter.md index d4eb9c6f3addf..bdd46cffb7df4 100644 --- a/perception/ground_segmentation/docs/scan-ground-filter.md +++ b/perception/ground_segmentation/docs/scan-ground-filter.md @@ -19,13 +19,13 @@ This algorithm works by following steps, ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ## Parameters ### Node Parameters -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). #### Core Parameters diff --git a/perception/ground_segmentation/package.xml b/perception/ground_segmentation/package.xml index 1b807b393b739..4358470c0b062 100644 --- a/perception/ground_segmentation/package.xml +++ b/perception/ground_segmentation/package.xml @@ -19,11 +19,11 @@ ament_cmake_auto autoware_cmake + autoware_pointcloud_preprocessor autoware_vehicle_info_utils libopencv-dev pcl_conversions pcl_ros - pointcloud_preprocessor rclcpp rclcpp_components sensor_msgs diff --git a/perception/ground_segmentation/src/ransac_ground_filter/node.cpp b/perception/ground_segmentation/src/ransac_ground_filter/node.cpp index 25e29c5b9f21a..dd5ce96a858cd 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter/node.cpp +++ b/perception/ground_segmentation/src/ransac_ground_filter/node.cpp @@ -80,7 +80,7 @@ PlaneBasis getPlaneBasis(const Eigen::Vector3d & plane_normal) return basis; } -using pointcloud_preprocessor::get_param; +using autoware::pointcloud_preprocessor::get_param; RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptions & options) : Filter("RANSACGroundFilter", options) diff --git a/perception/ground_segmentation/src/ransac_ground_filter/node.hpp b/perception/ground_segmentation/src/ransac_ground_filter/node.hpp index ebdd28f26ebe8..e173fe131602f 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter/node.hpp +++ b/perception/ground_segmentation/src/ransac_ground_filter/node.hpp @@ -15,7 +15,7 @@ #ifndef RANSAC_GROUND_FILTER__NODE_HPP_ #define RANSAC_GROUND_FILTER__NODE_HPP_ -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include @@ -54,7 +54,7 @@ struct RGB double b = 0.0; }; -class RANSACGroundFilterComponent : public pointcloud_preprocessor::Filter +class RANSACGroundFilterComponent : public autoware::pointcloud_preprocessor::Filter { using PointType = pcl::PointXYZ; diff --git a/perception/ground_segmentation/src/ray_ground_filter/node.cpp b/perception/ground_segmentation/src/ray_ground_filter/node.cpp index f07db15615739..fd8fcd4dc29e7 100644 --- a/perception/ground_segmentation/src/ray_ground_filter/node.cpp +++ b/perception/ground_segmentation/src/ray_ground_filter/node.cpp @@ -36,7 +36,7 @@ namespace autoware::ground_segmentation { -using pointcloud_preprocessor::get_param; +using autoware::pointcloud_preprocessor::get_param; RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & options) : Filter("RayGroundFilter", options) diff --git a/perception/ground_segmentation/src/ray_ground_filter/node.hpp b/perception/ground_segmentation/src/ray_ground_filter/node.hpp index d3be2e60c4262..a7b038a5bfe25 100644 --- a/perception/ground_segmentation/src/ray_ground_filter/node.hpp +++ b/perception/ground_segmentation/src/ray_ground_filter/node.hpp @@ -58,8 +58,8 @@ #include #endif +#include "autoware/pointcloud_preprocessor/filter.hpp" #include "gencolors.hpp" -#include "pointcloud_preprocessor/filter.hpp" #include #include @@ -81,7 +81,7 @@ using Polygon = bg::model::polygon; namespace autoware::ground_segmentation { -class RayGroundFilterComponent : public pointcloud_preprocessor::Filter +class RayGroundFilterComponent : public autoware::pointcloud_preprocessor::Filter { typedef pcl::PointXYZ PointType_; diff --git a/perception/ground_segmentation/src/scan_ground_filter/node.cpp b/perception/ground_segmentation/src/scan_ground_filter/node.cpp index 01116c5bdce5f..2745606697a20 100644 --- a/perception/ground_segmentation/src/scan_ground_filter/node.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter/node.cpp @@ -25,15 +25,15 @@ namespace autoware::ground_segmentation { +using autoware::pointcloud_preprocessor::get_param; using autoware::universe_utils::calcDistance3d; using autoware::universe_utils::deg2rad; using autoware::universe_utils::normalizeDegree; using autoware::universe_utils::normalizeRadian; using autoware::vehicle_info_utils::VehicleInfoUtils; -using pointcloud_preprocessor::get_param; ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & options) -: pointcloud_preprocessor::Filter("ScanGroundFilter", options) +: autoware::pointcloud_preprocessor::Filter("ScanGroundFilter", options) { // set initial parameters { @@ -582,7 +582,7 @@ void ScanGroundFilterComponent::extractObjectPoints( void ScanGroundFilterComponent::faster_filter( const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, PointCloud2 & output, - [[maybe_unused]] const pointcloud_preprocessor::TransformInfo & transform_info) + [[maybe_unused]] const autoware::pointcloud_preprocessor::TransformInfo & transform_info) { std::scoped_lock lock(mutex_); stop_watch_ptr_->toc("processing_time", true); diff --git a/perception/ground_segmentation/src/scan_ground_filter/node.hpp b/perception/ground_segmentation/src/scan_ground_filter/node.hpp index 67a844eee75c5..87da36826c888 100644 --- a/perception/ground_segmentation/src/scan_ground_filter/node.hpp +++ b/perception/ground_segmentation/src/scan_ground_filter/node.hpp @@ -15,9 +15,9 @@ #ifndef SCAN_GROUND_FILTER__NODE_HPP_ #define SCAN_GROUND_FILTER__NODE_HPP_ +#include "autoware/pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/transform_info.hpp" #include "autoware_vehicle_info_utils/vehicle_info.hpp" -#include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/transform_info.hpp" #include @@ -44,7 +44,7 @@ namespace autoware::ground_segmentation { using autoware::vehicle_info_utils::VehicleInfo; -class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter +class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filter { private: // classified point label @@ -152,7 +152,7 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter // conform to new API virtual void faster_filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, - const pointcloud_preprocessor::TransformInfo & transform_info); + const autoware::pointcloud_preprocessor::TransformInfo & transform_info); tf2_ros::Buffer tf_buffer_{get_clock()}; tf2_ros::TransformListener tf_listener_{tf_buffer_}; diff --git a/perception/ground_segmentation/test/test_scan_ground_filter.cpp b/perception/ground_segmentation/test/test_scan_ground_filter.cpp index f5faecd59d6d3..3fb4ead672ffe 100644 --- a/perception/ground_segmentation/test/test_scan_ground_filter.cpp +++ b/perception/ground_segmentation/test/test_scan_ground_filter.cpp @@ -171,7 +171,7 @@ class ScanGroundFilterTest : public ::testing::Test // wrapper function to test private function filter void filter(sensor_msgs::msg::PointCloud2 & out_cloud) { - pointcloud_preprocessor::TransformInfo transform_info; + autoware::pointcloud_preprocessor::TransformInfo transform_info; scan_ground_filter_->faster_filter(input_msg_ptr_, nullptr, out_cloud, transform_info); } diff --git a/perception/occupancy_grid_map_outlier_filter/package.xml b/perception/occupancy_grid_map_outlier_filter/package.xml index e92e5edb4b084..af6feb2aefba7 100644 --- a/perception/occupancy_grid_map_outlier_filter/package.xml +++ b/perception/occupancy_grid_map_outlier_filter/package.xml @@ -18,13 +18,13 @@ autoware_cmake autoware_lanelet2_extension + autoware_pointcloud_preprocessor autoware_universe_utils libpcl-all-dev message_filters nav_msgs pcl_conversions pcl_ros - pointcloud_preprocessor rclcpp rclcpp_components sensor_msgs diff --git a/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.hpp b/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.hpp index e9402d6416cbd..b7ec3ffeac6df 100644 --- a/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.hpp +++ b/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.hpp @@ -15,8 +15,8 @@ #ifndef OCCUPANCY_GRID_MAP_OUTLIER_FILTER_NODE_HPP_ #define OCCUPANCY_GRID_MAP_OUTLIER_FILTER_NODE_HPP_ +#include "autoware/pointcloud_preprocessor/filter.hpp" #include "autoware/universe_utils/ros/published_time_publisher.hpp" -#include "pointcloud_preprocessor/filter.hpp" #include #include diff --git a/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py index ef40839d2a5aa..d868f139774a4 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py @@ -98,7 +98,7 @@ def get_downsample_filter_node(setting: dict) -> ComposableNode: voxel_size = setting["voxel_size"] node_name = setting["node_name"] return ComposableNode( - package="pointcloud_preprocessor", + package="autoware_pointcloud_preprocessor", plugin=plugin_str, name=node_name, remappings=[ @@ -125,7 +125,7 @@ def get_downsample_preprocess_nodes(voxel_size: float, raw_pointcloud_topics: li ] # `/sensing/lidar/top/pointcloud` -> `top processed_pointcloud_topic: str = frame_name + "/raw/downsample/pointcloud" raw_settings = { - "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "plugin": "autoware::pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", "node_name": "raw_pc_downsample_filter_" + frame_name, "input_topic": raw_pointcloud_topic, "output_topic": processed_pointcloud_topic, @@ -133,7 +133,7 @@ def get_downsample_preprocess_nodes(voxel_size: float, raw_pointcloud_topics: li } nodes.append(get_downsample_filter_node(raw_settings)) obstacle_settings = { - "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "plugin": "autoware::pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", "node_name": "obstacle_pc_downsample_filter", "input_topic": LaunchConfiguration("input/obstacle_pointcloud"), "output_topic": "/perception/occupancy_grid_map/obstacle/downsample/pointcloud", diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index bb5ef025a7e47..7093e7a26fe44 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -31,7 +31,7 @@ def get_downsample_filter_node(setting: dict) -> ComposableNode: voxel_size = setting["voxel_size"] node_name = setting["node_name"] return ComposableNode( - package="pointcloud_preprocessor", + package="autoware_pointcloud_preprocessor", plugin=plugin_str, name=node_name, remappings=[ @@ -51,14 +51,14 @@ def get_downsample_filter_node(setting: dict) -> ComposableNode: def get_downsample_preprocess_nodes(voxel_size: float) -> list: raw_settings = { - "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "plugin": "autoware::pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", "node_name": "raw_pc_downsample_filter", "input_topic": LaunchConfiguration("input/raw_pointcloud"), "output_topic": "raw/downsample/pointcloud", "voxel_size": voxel_size, } obstacle_settings = { - "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "plugin": "autoware::pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", "node_name": "obstacle_pc_downsample_filter", "input_topic": LaunchConfiguration("input/obstacle_pointcloud"), "output_topic": "obstacle/downsample/pointcloud", diff --git a/perception/probabilistic_occupancy_grid_map/package.xml b/perception/probabilistic_occupancy_grid_map/package.xml index d8647ae2ba744..ba8d4108ffcd2 100644 --- a/perception/probabilistic_occupancy_grid_map/package.xml +++ b/perception/probabilistic_occupancy_grid_map/package.xml @@ -31,18 +31,18 @@ tf2_ros tf2_sensor_msgs - pointcloud_preprocessor + autoware_pointcloud_preprocessor pointcloud_to_laserscan ament_cmake_gtest ament_lint_auto autoware_lint_common + autoware_pointcloud_preprocessor launch launch_ros launch_testing launch_testing_ament_cmake launch_testing_ros - pointcloud_preprocessor ament_cmake diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt similarity index 81% rename from sensing/pointcloud_preprocessor/CMakeLists.txt rename to sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index 76b9cc91ea586..744bac480e058 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(pointcloud_preprocessor) +project(autoware_pointcloud_preprocessor) find_package(autoware_cmake REQUIRED) autoware_package() @@ -98,99 +98,99 @@ target_link_libraries(pointcloud_preprocessor_filter # ========== Time synchronizer ========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::PointCloudDataSynchronizerComponent" + PLUGIN "autoware::pointcloud_preprocessor::PointCloudDataSynchronizerComponent" EXECUTABLE time_synchronizer_node) # ========== Concatenate data ========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::PointCloudConcatenationComponent" + PLUGIN "autoware::pointcloud_preprocessor::PointCloudConcatenationComponent" EXECUTABLE concatenate_pointclouds_node) # ========== Concatenate and Sync data ========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent" + PLUGIN "autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent" EXECUTABLE concatenate_data_node) # ========== CropBox ========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::CropBoxFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::CropBoxFilterComponent" EXECUTABLE crop_box_filter_node) # ========== Down Sampler Filter ========== # -- Voxel Grid Downsample Filter -- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::VoxelGridDownsampleFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::VoxelGridDownsampleFilterComponent" EXECUTABLE voxel_grid_downsample_filter_node) # -- Pickup Based Voxel Grid Downsample Filter -- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent" EXECUTABLE pickup_based_voxel_grid_downsample_filter_node) # -- Random Downsample Filter -- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::RandomDownsampleFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::RandomDownsampleFilterComponent" EXECUTABLE random_downsample_filter_node) rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::ApproximateDownsampleFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::ApproximateDownsampleFilterComponent" EXECUTABLE approximate_downsample_filter_node) # ========== Outlier Filter ========== # -- Ring Outlier Filter -- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::RingOutlierFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::RingOutlierFilterComponent" EXECUTABLE ring_outlier_filter_node) # -- Voxel Grid Outlier Filter -- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::VoxelGridOutlierFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::VoxelGridOutlierFilterComponent" EXECUTABLE voxel_grid_outlier_filter_node) # -- Radius Search 2D Outlier Filter -- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::RadiusSearch2DOutlierFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::RadiusSearch2DOutlierFilterComponent" EXECUTABLE radius_search_2d_outlier_filter_node) # -- DualReturn Outlier Filter-- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::DualReturnOutlierFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::DualReturnOutlierFilterComponent" EXECUTABLE dual_return_outlier_filter_node) # ========== Passthrough Filter ========== # -- Passthrough Filter -- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::PassThroughFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::PassThroughFilterComponent" EXECUTABLE passthrough_filter_node) # -- Passthrough Filter Uint16 -- rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::PassThroughFilterUInt16Component" + PLUGIN "autoware::pointcloud_preprocessor::PassThroughFilterUInt16Component" EXECUTABLE passthrough_filter_uint16_node) # ========== Pointcloud Accumulator Filter ========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::PointcloudAccumulatorComponent" + PLUGIN "autoware::pointcloud_preprocessor::PointcloudAccumulatorComponent" EXECUTABLE pointcloud_accumulator_node) # ========== Vector Map Filter ========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::Lanelet2MapFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::Lanelet2MapFilterComponent" EXECUTABLE vector_map_filter_node) # ========== Distortion Corrector ========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::DistortionCorrectorComponent" + PLUGIN "autoware::pointcloud_preprocessor::DistortionCorrectorComponent" EXECUTABLE distortion_corrector_node) # ========== Blockage Diagnostics =========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::BlockageDiagComponent" + PLUGIN "autoware::pointcloud_preprocessor::BlockageDiagComponent" EXECUTABLE blockage_diag_node) # ========== PolygonRemover ========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::PolygonRemoverComponent" + PLUGIN "autoware::pointcloud_preprocessor::PolygonRemoverComponent" EXECUTABLE polygon_remover_node) set(CGAL_DO_NOT_WARN_ABOUT_CMAKE_BUILD_TYPE TRUE) @@ -198,7 +198,7 @@ target_link_libraries(polygon_remover_node gmp CGAL CGAL::CGAL CGAL::CGAL_Core) # ========== Vector Map Inside Area Filter =========== rclcpp_components_register_node(pointcloud_preprocessor_filter - PLUGIN "pointcloud_preprocessor::VectorMapInsideAreaFilterComponent" + PLUGIN "autoware::pointcloud_preprocessor::VectorMapInsideAreaFilterComponent" EXECUTABLE vector_map_inside_area_filter_node) install( diff --git a/sensing/pointcloud_preprocessor/README.md b/sensing/autoware_pointcloud_preprocessor/README.md similarity index 96% rename from sensing/pointcloud_preprocessor/README.md rename to sensing/autoware_pointcloud_preprocessor/README.md index 5c6402efdf23d..4424259a52daa 100644 --- a/sensing/pointcloud_preprocessor/README.md +++ b/sensing/autoware_pointcloud_preprocessor/README.md @@ -1,8 +1,8 @@ -# pointcloud_preprocessor +# autoware_pointcloud_preprocessor ## Purpose -The `pointcloud_preprocessor` is a package that includes the following filters: +The `autoware_pointcloud_preprocessor` is a package that includes the following filters: - removing outlier points - cropping @@ -56,7 +56,7 @@ Detail description of each filter's algorithm is in the following links. ## Assumptions / Known limits -`pointcloud_preprocessor::Filter` is implemented based on pcl_perception [1] because +`autoware::pointcloud_preprocessor::Filter` is implemented based on pcl_perception [1] because of [this issue](https://github.com/ros-perception/perception_pcl/issues/9). ## Measuring the performance diff --git a/sensing/pointcloud_preprocessor/config/blockage_diagnostics_param_file.yaml b/sensing/autoware_pointcloud_preprocessor/config/blockage_diagnostics_param_file.yaml similarity index 100% rename from sensing/pointcloud_preprocessor/config/blockage_diagnostics_param_file.yaml rename to sensing/autoware_pointcloud_preprocessor/config/blockage_diagnostics_param_file.yaml diff --git a/sensing/pointcloud_preprocessor/config/distortion_corrector_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml similarity index 100% rename from sensing/pointcloud_preprocessor/config/distortion_corrector_node.param.yaml rename to sensing/autoware_pointcloud_preprocessor/config/distortion_corrector_node.param.yaml diff --git a/sensing/pointcloud_preprocessor/config/processing_time_ms.xml b/sensing/autoware_pointcloud_preprocessor/config/processing_time_ms.xml similarity index 100% rename from sensing/pointcloud_preprocessor/config/processing_time_ms.xml rename to sensing/autoware_pointcloud_preprocessor/config/processing_time_ms.xml diff --git a/sensing/pointcloud_preprocessor/docs/blockage_diag.md b/sensing/autoware_pointcloud_preprocessor/docs/blockage_diag.md similarity index 98% rename from sensing/pointcloud_preprocessor/docs/blockage_diag.md rename to sensing/autoware_pointcloud_preprocessor/docs/blockage_diag.md index 082ae180fa3c9..b6f858ada3a98 100644 --- a/sensing/pointcloud_preprocessor/docs/blockage_diag.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/blockage_diag.md @@ -28,7 +28,7 @@ The area of noise is found by erosion and dilation these black pixels. ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Input diff --git a/sensing/pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md similarity index 100% rename from sensing/pointcloud_preprocessor/docs/concatenate-data.md rename to sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md diff --git a/sensing/pointcloud_preprocessor/docs/crop-box-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/crop-box-filter.md similarity index 84% rename from sensing/pointcloud_preprocessor/docs/crop-box-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/crop-box-filter.md index b6bd960c99919..4539a85e26a1d 100644 --- a/sensing/pointcloud_preprocessor/docs/crop-box-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/crop-box-filter.md @@ -10,13 +10,13 @@ The `crop_box_filter` is a node that removes points with in a given box region. ## Inputs / Outputs -This implementation inherit `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherit `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ## Parameters ### Node Parameters -This implementation inherit `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherit `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Core Parameters diff --git a/sensing/pointcloud_preprocessor/docs/distortion-corrector.md b/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md similarity index 93% rename from sensing/pointcloud_preprocessor/docs/distortion-corrector.md rename to sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md index 033e82607057a..ab5a07b5279bc 100644 --- a/sensing/pointcloud_preprocessor/docs/distortion-corrector.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md @@ -36,12 +36,12 @@ Please note that the processing time difference between the two distortion metho ### Core Parameters -{{ json_to_markdown("sensing/pointcloud_preprocessor/schema/distortion_corrector_node.schema.json") }} +{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json") }} ## Launch ```bash -ros2 launch pointcloud_preprocessor distortion_corrector.launch.xml +ros2 launch autoware_pointcloud_preprocessor distortion_corrector.launch.xml ``` ## Assumptions / Known limits diff --git a/sensing/pointcloud_preprocessor/docs/downsample-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/downsample-filter.md similarity index 91% rename from sensing/pointcloud_preprocessor/docs/downsample-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/downsample-filter.md index 25faf62b765bc..ac721171cb014 100644 --- a/sensing/pointcloud_preprocessor/docs/downsample-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/downsample-filter.md @@ -24,13 +24,13 @@ This algorithm samples a single actual point existing within the voxel, not the ## Inputs / Outputs -These implementations inherit `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +These implementations inherit `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ## Parameters ### Note Parameters -These implementations inherit `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +These implementations inherit `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Core Parameters diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md similarity index 96% rename from sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md index d5993a803fa87..6c9a7ed14c2eb 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -32,7 +32,7 @@ The below picture shows the ROI options. ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Output @@ -46,7 +46,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref ### Node Parameters -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Core Parameters diff --git a/sensing/pointcloud_preprocessor/docs/image/blockage_diag.png b/sensing/autoware_pointcloud_preprocessor/docs/image/blockage_diag.png similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/blockage_diag.png rename to sensing/autoware_pointcloud_preprocessor/docs/image/blockage_diag.png diff --git a/sensing/pointcloud_preprocessor/docs/image/blockage_diag_flowchart.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/blockage_diag_flowchart.drawio.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/blockage_diag_flowchart.drawio.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/blockage_diag_flowchart.drawio.svg diff --git a/sensing/pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg diff --git a/sensing/pointcloud_preprocessor/docs/image/distortion_corrector.jpg b/sensing/autoware_pointcloud_preprocessor/docs/image/distortion_corrector.jpg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/distortion_corrector.jpg rename to sensing/autoware_pointcloud_preprocessor/docs/image/distortion_corrector.jpg diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png b/sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png rename to sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-dual_return_ROI_setting_options.png diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_detail.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-dual_return_detail.drawio.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_detail.drawio.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-dual_return_detail.drawio.svg diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_overall.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-dual_return_overall.drawio.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/outlier_filter-dual_return_overall.drawio.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-dual_return_overall.drawio.svg diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-radius_search_2d.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-radius_search_2d.drawio.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/outlier_filter-radius_search_2d.drawio.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-radius_search_2d.drawio.svg diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-return_type.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-return_type.drawio.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/outlier_filter-return_type.drawio.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-return_type.drawio.svg diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-ring.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-ring.drawio.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/outlier_filter-ring.drawio.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-ring.drawio.svg diff --git a/sensing/pointcloud_preprocessor/docs/image/outlier_filter-voxel_grid.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-voxel_grid.drawio.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/outlier_filter-voxel_grid.drawio.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/outlier_filter-voxel_grid.drawio.svg diff --git a/sensing/pointcloud_preprocessor/docs/image/pointcloud_preprocess_pipeline.drawio.png b/sensing/autoware_pointcloud_preprocessor/docs/image/pointcloud_preprocess_pipeline.drawio.png similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/pointcloud_preprocess_pipeline.drawio.png rename to sensing/autoware_pointcloud_preprocessor/docs/image/pointcloud_preprocess_pipeline.drawio.png diff --git a/sensing/pointcloud_preprocessor/docs/image/vector_map_inside_area_filter_overview.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/vector_map_inside_area_filter_overview.svg similarity index 100% rename from sensing/pointcloud_preprocessor/docs/image/vector_map_inside_area_filter_overview.svg rename to sensing/autoware_pointcloud_preprocessor/docs/image/vector_map_inside_area_filter_overview.svg diff --git a/sensing/pointcloud_preprocessor/docs/outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/outlier-filter.md similarity index 100% rename from sensing/pointcloud_preprocessor/docs/outlier-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/outlier-filter.md diff --git a/sensing/pointcloud_preprocessor/docs/passthrough-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md similarity index 100% rename from sensing/pointcloud_preprocessor/docs/passthrough-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md diff --git a/sensing/pointcloud_preprocessor/docs/pointcloud-accumulator.md b/sensing/autoware_pointcloud_preprocessor/docs/pointcloud-accumulator.md similarity index 100% rename from sensing/pointcloud_preprocessor/docs/pointcloud-accumulator.md rename to sensing/autoware_pointcloud_preprocessor/docs/pointcloud-accumulator.md diff --git a/sensing/pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md similarity index 88% rename from sensing/pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md index 19d5c348afff5..d0d621b586da6 100644 --- a/sensing/pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/radius-search-2d-outlier-filter.md @@ -14,13 +14,13 @@ The description above is quoted from [1]. `pcl::search::KdTree` [2] is used to i ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ## Parameters ### Node Parameters -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Core Parameters diff --git a/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/ring-outlier-filter.md similarity index 95% rename from sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/ring-outlier-filter.md index 0a179ddf6a8ef..7f2efe90a674f 100644 --- a/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/ring-outlier-filter.md @@ -46,13 +46,13 @@ stop ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ## Parameters ### Node Parameters -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Core Parameters diff --git a/sensing/pointcloud_preprocessor/docs/vector-map-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/vector-map-filter.md similarity index 100% rename from sensing/pointcloud_preprocessor/docs/vector-map-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/vector-map-filter.md diff --git a/sensing/pointcloud_preprocessor/docs/vector-map-inside-area-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/vector-map-inside-area-filter.md similarity index 93% rename from sensing/pointcloud_preprocessor/docs/vector-map-inside-area-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/vector-map-inside-area-filter.md index 8e31dfb203d2b..1b6f86a7e4f27 100644 --- a/sensing/pointcloud_preprocessor/docs/vector-map-inside-area-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/vector-map-inside-area-filter.md @@ -16,7 +16,7 @@ The `vector_map_inside_area_filter` is a node that removes points inside the vec ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, so please see also [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, so please see also [README](../README.md). ### Input diff --git a/sensing/pointcloud_preprocessor/docs/voxel-grid-outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/voxel-grid-outlier-filter.md similarity index 85% rename from sensing/pointcloud_preprocessor/docs/voxel-grid-outlier-filter.md rename to sensing/autoware_pointcloud_preprocessor/docs/voxel-grid-outlier-filter.md index 0c1905e810fec..d99b54ef09a73 100644 --- a/sensing/pointcloud_preprocessor/docs/voxel-grid-outlier-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/voxel-grid-outlier-filter.md @@ -13,13 +13,13 @@ The [radius_search_2d_outlier_filter](./radius-search-2d-outlier-filter.md) is b ## Inputs / Outputs -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ## Parameters ### Node Parameters -This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). +This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, please refer [README](../README.md). ### Core Parameters diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp similarity index 88% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp index dd24c83761878..18f6c3851866d 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_ -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include @@ -38,12 +38,12 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; -class BlockageDiagComponent : public pointcloud_preprocessor::Filter +class BlockageDiagComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -103,6 +103,6 @@ class BlockageDiagComponent : public pointcloud_preprocessor::Filter explicit BlockageDiagComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp similarity index 94% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp index 619a0b8520b97..2443e45fe4c63 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp @@ -49,8 +49,8 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ #include #include @@ -85,7 +85,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using autoware_point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; @@ -189,6 +189,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node std::unique_ptr debug_publisher_; }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp similarity index 94% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp index 77717c51e6981..36b1910a4d798 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp @@ -49,8 +49,8 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ -#define POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ #include #include @@ -84,7 +84,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using autoware_point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; @@ -176,6 +176,6 @@ class PointCloudConcatenationComponent : public rclcpp::Node std::unique_ptr debug_publisher_; }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_POINTCLOUDS_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp similarity index 86% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp index 1406679ce0dba..09b5c7fd5f5fa 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp @@ -50,11 +50,11 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_ -#include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/transform_info.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/transform_info.hpp" #include @@ -62,9 +62,9 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class CropBoxFilterComponent : public pointcloud_preprocessor::Filter +class CropBoxFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -102,6 +102,6 @@ class CropBoxFilterComponent : public pointcloud_preprocessor::Filter PCL_MAKE_ALIGNED_OPERATOR_NEW explicit CropBoxFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp similarity index 94% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index e37329a9a4cc3..8226cb6eb774c 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ -#define POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ #include #include @@ -42,7 +42,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { class DistortionCorrectorBase @@ -170,6 +170,6 @@ class DistortionCorrector3D : public DistortionCorrector const std::string & base_frame, const std::string & lidar_frame) override; }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp similarity index 81% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp index 162170b193827..0d8c9436bda4b 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ -#define POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ -#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" +#include "autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" #include #include @@ -29,7 +29,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using rcl_interfaces::msg::SetParametersResult; using sensor_msgs::msg::PointCloud2; @@ -60,6 +60,6 @@ class DistortionCorrectorComponent : public rclcpp::Node void onImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/approximate_downsample_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/approximate_downsample_filter_nodelet.hpp similarity index 82% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/approximate_downsample_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/approximate_downsample_filter_nodelet.hpp index 70dcdcab1c2e6..d5d2750442a2f 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/approximate_downsample_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/approximate_downsample_filter_nodelet.hpp @@ -48,10 +48,10 @@ * $Id: voxel_grid.cpp 35876 2011-02-09 01:04:36Z rusu $ * */ -#ifndef POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__APPROXIMATE_DOWNSAMPLE_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__APPROXIMATE_DOWNSAMPLE_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__APPROXIMATE_DOWNSAMPLE_FILTER_NODELET_HPP_ // NOLINT +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__APPROXIMATE_DOWNSAMPLE_FILTER_NODELET_HPP_ // NOLINT -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include @@ -60,9 +60,9 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class ApproximateDownsampleFilterComponent : public pointcloud_preprocessor::Filter +class ApproximateDownsampleFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: void filter( @@ -80,6 +80,8 @@ class ApproximateDownsampleFilterComponent : public pointcloud_preprocessor::Fil PCL_MAKE_ALIGNED_OPERATOR_NEW explicit ApproximateDownsampleFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__APPROXIMATE_DOWNSAMPLE_FILTER_NODELET_HPP_ +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__APPROXIMATE_DOWNSAMPLE_FILTER_NODELET_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp similarity index 94% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp index 379c4c79e555a..89d6ea51a7283 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp @@ -14,7 +14,7 @@ #pragma once -#include "pointcloud_preprocessor/transform_info.hpp" +#include "autoware/pointcloud_preprocessor/transform_info.hpp" #include #include @@ -23,7 +23,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { class FasterVoxelGridDownsampleFilter @@ -96,4 +96,4 @@ class FasterVoxelGridDownsampleFilter const TransformInfo & transform_info); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp similarity index 76% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp index a923473ecbe36..9a1f2780be11b 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ -#define POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ // NOLINT +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ // NOLINT -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include @@ -26,7 +26,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { /** * @class PickupBasedVoxelGridDownsampleFilterComponent @@ -36,7 +36,8 @@ namespace pointcloud_preprocessor * and picking a representative point for each voxel. It's useful for reducing computational * load when processing large point clouds. */ -class PickupBasedVoxelGridDownsampleFilterComponent : public pointcloud_preprocessor::Filter +class PickupBasedVoxelGridDownsampleFilterComponent +: public autoware::pointcloud_preprocessor::Filter { protected: void filter( @@ -57,8 +58,8 @@ class PickupBasedVoxelGridDownsampleFilterComponent : public pointcloud_preproce PCL_MAKE_ALIGNED_OPERATOR_NEW explicit PickupBasedVoxelGridDownsampleFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor // clang-format off -#endif // POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ // NOLINT +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ // NOLINT // clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp similarity index 83% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp index c5a30fba37156..f820793fb86f8 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp @@ -48,18 +48,18 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_ -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class RandomDownsampleFilterComponent : public pointcloud_preprocessor::Filter +class RandomDownsampleFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: void filter( @@ -78,6 +78,8 @@ class RandomDownsampleFilterComponent : public pointcloud_preprocessor::Filter PCL_MAKE_ALIGNED_OPERATOR_NEW explicit RandomDownsampleFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_ +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp similarity index 82% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp index ae285b4fa9239..1af2eb5b04552 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp @@ -48,20 +48,20 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ // NOLINT +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ // NOLINT -#include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/transform_info.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/transform_info.hpp" #include #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class VoxelGridDownsampleFilterComponent : public pointcloud_preprocessor::Filter +class VoxelGridDownsampleFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: void filter( @@ -88,6 +88,8 @@ class VoxelGridDownsampleFilterComponent : public pointcloud_preprocessor::Filte PCL_MAKE_ALIGNED_OPERATOR_NEW explicit VoxelGridDownsampleFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__VOXEL_GRID_DOWNSAMPLE_FILTER_NODELET_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp similarity index 97% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp index ce003f58dcc49..a6e113412231a 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/filter.hpp @@ -49,10 +49,10 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__FILTER_HPP_ -#define POINTCLOUD_PREPROCESSOR__FILTER_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__FILTER_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__FILTER_HPP_ -#include "pointcloud_preprocessor/transform_info.hpp" +#include "autoware/pointcloud_preprocessor/transform_info.hpp" #include #include @@ -84,7 +84,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { namespace sync_policies = message_filters::sync_policies; @@ -302,6 +302,6 @@ class Filter : public rclcpp::Node void setupTF(); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__FILTER_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__FILTER_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp similarity index 82% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp index 940b24ae30569..b8aba769b17a5 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include @@ -38,12 +38,12 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; -class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter +class DualReturnOutlierFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -91,6 +91,8 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter explicit DualReturnOutlierFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp similarity index 71% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp index 19c36a1bdb1ce..ffb737b0b9b06 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include @@ -26,9 +26,9 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class RadiusSearch2DOutlierFilterComponent : public pointcloud_preprocessor::Filter +class RadiusSearch2DOutlierFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -52,6 +52,8 @@ class RadiusSearch2DOutlierFilterComponent : public pointcloud_preprocessor::Fil PCL_MAKE_ALIGNED_OPERATOR_NEW explicit RadiusSearch2DOutlierFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp similarity index 85% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp index 08fbfe73f2744..caedeac62b88a 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_ +#include "autoware/pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/transform_info.hpp" #include "autoware_point_types/types.hpp" -#include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/transform_info.hpp" #include #include @@ -33,11 +33,11 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using point_cloud_msg_wrapper::PointCloud2Modifier; -class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter +class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: using InputPointIndex = autoware_point_types::PointXYZIRCAEDTIndex; @@ -107,5 +107,5 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter explicit RingOutlierFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_ +} // namespace autoware::pointcloud_preprocessor +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_nodelet.hpp similarity index 71% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_nodelet.hpp index f312b6c0b8505..4ec50c53c2393 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_nodelet.hpp @@ -12,19 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_ -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class VoxelGridOutlierFilterComponent : public pointcloud_preprocessor::Filter +class VoxelGridOutlierFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -48,6 +48,6 @@ class VoxelGridOutlierFilterComponent : public pointcloud_preprocessor::Filter PCL_MAKE_ALIGNED_OPERATOR_NEW explicit VoxelGridOutlierFilterComponent(const rclcpp::NodeOptions & option); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp similarity index 84% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp index 5fafa7383b54e..bbb2c0b113658 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp @@ -48,18 +48,18 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class PassThroughFilterComponent : public pointcloud_preprocessor::Filter +class PassThroughFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -75,6 +75,6 @@ class PassThroughFilterComponent : public pointcloud_preprocessor::Filter PCL_MAKE_ALIGNED_OPERATOR_NEW explicit PassThroughFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp similarity index 63% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp index 678da0fbe6b86..0ffb50dc65092 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp @@ -12,19 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT -#include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp" #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class PassThroughFilterUInt16Component : public pointcloud_preprocessor::Filter +class PassThroughFilterUInt16Component : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -43,6 +43,8 @@ class PassThroughFilterUInt16Component : public pointcloud_preprocessor::Filter PCL_MAKE_ALIGNED_OPERATOR_NEW explicit PassThroughFilterUInt16Component(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp similarity index 98% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp index 8115a46c1ffbc..7da891f20955b 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp @@ -50,8 +50,8 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_UINT16_HPP_ -#define POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_UINT16_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_UINT16_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_UINT16_HPP_ #include #include @@ -471,4 +471,4 @@ void pcl::PassThroughUInt16::applyFilterIndices(std::vector & indic #include #endif -#endif // POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_UINT16_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_UINT16_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp similarity index 67% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp index ca4f0d6ccd2be..6646426a29b99 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class PointcloudAccumulatorComponent : public pointcloud_preprocessor::Filter +class PointcloudAccumulatorComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -43,6 +43,8 @@ class PointcloudAccumulatorComponent : public pointcloud_preprocessor::Filter PCL_MAKE_ALIGNED_OPERATOR_NEW explicit PointcloudAccumulatorComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ +// clang-format off +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp similarity index 78% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp index 4d2e66eea700e..3054a4454fb00 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__POLYGON_REMOVER__POLYGON_REMOVER_HPP_ -#define POINTCLOUD_PREPROCESSOR__POLYGON_REMOVER__POLYGON_REMOVER_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__POLYGON_REMOVER__POLYGON_REMOVER_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__POLYGON_REMOVER__POLYGON_REMOVER_HPP_ -#include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/utility/geometry.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/utility/geometry.hpp" #include #include @@ -27,9 +27,9 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class PolygonRemoverComponent : public pointcloud_preprocessor::Filter +class PolygonRemoverComponent : public autoware::pointcloud_preprocessor::Filter { protected: virtual void filter( @@ -60,6 +60,6 @@ class PolygonRemoverComponent : public pointcloud_preprocessor::Filter PCL_MAKE_ALIGNED_OPERATOR_NEW explicit PolygonRemoverComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__POLYGON_REMOVER__POLYGON_REMOVER_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__POLYGON_REMOVER__POLYGON_REMOVER_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp similarity index 95% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp index 2dc98a571ff2c..00704b20b85ef 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp @@ -49,8 +49,8 @@ * */ -#ifndef POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODELET_HPP_ #include #include @@ -85,7 +85,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using autoware_point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; @@ -186,6 +186,6 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node std::unique_ptr debug_publisher_; }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODELET_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODELET_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/transform_info.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/transform_info.hpp similarity index 91% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/transform_info.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/transform_info.hpp index a4806555695b5..9c4ba7c5ea7ea 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/transform_info.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/transform_info.hpp @@ -16,7 +16,7 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { /** @@ -40,4 +40,4 @@ struct TransformInfo bool need_transform; }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/geometry.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/geometry.hpp similarity index 90% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/geometry.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/geometry.hpp index 0175f88ceb89c..e4aacb1a80d6c 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/geometry.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/geometry.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ -#define POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ #include #include @@ -33,7 +33,7 @@ using K = CGAL::Exact_predicates_inexact_constructions_kernel; using PointCgal = K::Point_2; using PolygonCgal = std::vector; -namespace pointcloud_preprocessor::utils +namespace autoware::pointcloud_preprocessor::utils { /** * @brief convert ROS polygon to CGAL polygon @@ -81,6 +81,6 @@ void remove_polygon_cgal_from_cloud( bool point_within_cgal_polys( const pcl::PointXYZ & point, const std::vector & polyline_polygons); -} // namespace pointcloud_preprocessor::utils +} // namespace autoware::pointcloud_preprocessor::utils -#endif // POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/memory.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/memory.hpp similarity index 85% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/memory.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/memory.hpp index ef87a4f31457b..4810c5ce84130 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/memory.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/utility/memory.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ -#define POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ #include -namespace pointcloud_preprocessor::utils +namespace autoware::pointcloud_preprocessor::utils { /** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is to * say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */ @@ -35,6 +35,6 @@ bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::Poin * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */ bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::PointCloud2 & input); -} // namespace pointcloud_preprocessor::utils +} // namespace autoware::pointcloud_preprocessor::utils -#endif // POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp similarity index 89% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp index 2bc9e70c8e29b..4ba773ed618ac 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_ -#define POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_ #include #include @@ -44,7 +44,7 @@ using autoware::universe_utils::LinearRing2d; using autoware::universe_utils::MultiPoint2d; using autoware::universe_utils::Point2d; -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { class Lanelet2MapFilterComponent : public rclcpp::Node { @@ -95,6 +95,6 @@ class Lanelet2MapFilterComponent : public rclcpp::Node rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector & p); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp similarity index 70% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp index d28a6550123cf..a6b497b40cd77 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_ -#define POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_ -#include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/utility/geometry.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/utility/geometry.hpp" #include #include @@ -28,9 +28,9 @@ using autoware::universe_utils::MultiPoint2d; -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { -class VectorMapInsideAreaFilterComponent : public pointcloud_preprocessor::Filter +class VectorMapInsideAreaFilterComponent : public autoware::pointcloud_preprocessor::Filter { private: void filter( @@ -51,6 +51,6 @@ class VectorMapInsideAreaFilterComponent : public pointcloud_preprocessor::Filte explicit VectorMapInsideAreaFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor -#endif // POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_ +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_ diff --git a/sensing/pointcloud_preprocessor/launch/blockage_diag.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/blockage_diag.launch.xml similarity index 82% rename from sensing/pointcloud_preprocessor/launch/blockage_diag.launch.xml rename to sensing/autoware_pointcloud_preprocessor/launch/blockage_diag.launch.xml index 5a93cb950b827..281ddd7ce434e 100644 --- a/sensing/pointcloud_preprocessor/launch/blockage_diag.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/blockage_diag.launch.xml @@ -5,8 +5,8 @@ - - + + diff --git a/sensing/pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml similarity index 71% rename from sensing/pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml rename to sensing/autoware_pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml index d970aae102264..bde9ca9e59ddd 100644 --- a/sensing/pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml @@ -5,8 +5,8 @@ - - + + diff --git a/sensing/pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml similarity index 87% rename from sensing/pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml rename to sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml index db51e9bafc90e..c65996fbcdc65 100644 --- a/sensing/pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml @@ -8,7 +8,7 @@ - + diff --git a/sensing/pointcloud_preprocessor/launch/polygon_remover.launch.py b/sensing/autoware_pointcloud_preprocessor/launch/polygon_remover.launch.py similarity index 93% rename from sensing/pointcloud_preprocessor/launch/polygon_remover.launch.py rename to sensing/autoware_pointcloud_preprocessor/launch/polygon_remover.launch.py index 98bc5a6dd2699..801642bac79ac 100644 --- a/sensing/pointcloud_preprocessor/launch/polygon_remover.launch.py +++ b/sensing/autoware_pointcloud_preprocessor/launch/polygon_remover.launch.py @@ -23,7 +23,7 @@ def generate_launch_description(): ns = "pointcloud_preprocessor" - pkg = "pointcloud_preprocessor" + pkg = "autoware_pointcloud_preprocessor" param_file = os.path.join( get_package_share_directory("autoware_vehicle_info_utils"), "config/polygon_remover.yaml" @@ -34,7 +34,7 @@ def generate_launch_description(): my_component = ComposableNode( package=pkg, - plugin="pointcloud_preprocessor::PolygonRemoverComponent", + plugin="autoware::pointcloud_preprocessor::PolygonRemoverComponent", name="polygon_remover", parameters=[ { diff --git a/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py b/sensing/autoware_pointcloud_preprocessor/launch/preprocessor.launch.py similarity index 93% rename from sensing/pointcloud_preprocessor/launch/preprocessor.launch.py rename to sensing/autoware_pointcloud_preprocessor/launch/preprocessor.launch.py index d82c23152aee4..108cf6d4c4213 100644 --- a/sensing/pointcloud_preprocessor/launch/preprocessor.launch.py +++ b/sensing/autoware_pointcloud_preprocessor/launch/preprocessor.launch.py @@ -24,7 +24,7 @@ def launch_setup(context, *args, **kwargs): ns = "pointcloud_preprocessor" - pkg = "pointcloud_preprocessor" + pkg = "autoware_pointcloud_preprocessor" separate_concatenate_node_and_time_sync_node = LaunchConfiguration( "separate_concatenate_node_and_time_sync_node" @@ -36,7 +36,7 @@ def launch_setup(context, *args, **kwargs): if not is_separate_concatenate_node_and_time_sync_node: sync_and_concat_component = ComposableNode( package=pkg, - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", name="sync_and_concatenate_filter", remappings=[ ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), @@ -56,7 +56,7 @@ def launch_setup(context, *args, **kwargs): else: time_sync_component = ComposableNode( package=pkg, - plugin="pointcloud_preprocessor::PointCloudDataSynchronizerComponent", + plugin="autoware::pointcloud_preprocessor::PointCloudDataSynchronizerComponent", name="synchronizer_filter", remappings=[ ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), @@ -73,7 +73,7 @@ def launch_setup(context, *args, **kwargs): concat_component = ComposableNode( package=pkg, - plugin="pointcloud_preprocessor::PointCloudConcatenationComponent", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenationComponent", name="concatenate_filter", remappings=[("output", "points_raw/concatenated")], parameters=[ @@ -89,7 +89,7 @@ def launch_setup(context, *args, **kwargs): # set crop box filter as a component cropbox_component = ComposableNode( package=pkg, - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter", remappings=[ ( diff --git a/sensing/pointcloud_preprocessor/launch/preprocessor.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/preprocessor.launch.xml similarity index 88% rename from sensing/pointcloud_preprocessor/launch/preprocessor.launch.xml rename to sensing/autoware_pointcloud_preprocessor/launch/preprocessor.launch.xml index bba1a1b1c6a8c..81add45a62684 100644 --- a/sensing/pointcloud_preprocessor/launch/preprocessor.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/preprocessor.launch.xml @@ -9,7 +9,7 @@ - + diff --git a/sensing/pointcloud_preprocessor/launch/random_downsample_filter.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/random_downsample_filter.launch.xml similarity index 84% rename from sensing/pointcloud_preprocessor/launch/random_downsample_filter.launch.xml rename to sensing/autoware_pointcloud_preprocessor/launch/random_downsample_filter.launch.xml index edd4f6e92aa8d..c9d0bc3ce0608 100644 --- a/sensing/pointcloud_preprocessor/launch/random_downsample_filter.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/random_downsample_filter.launch.xml @@ -6,7 +6,7 @@ - + diff --git a/sensing/pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml similarity index 90% rename from sensing/pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml rename to sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml index c121a7f0af6ac..a9ed23e9faa3a 100644 --- a/sensing/pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml @@ -10,7 +10,7 @@ - + diff --git a/sensing/pointcloud_preprocessor/package.xml b/sensing/autoware_pointcloud_preprocessor/package.xml similarity index 94% rename from sensing/pointcloud_preprocessor/package.xml rename to sensing/autoware_pointcloud_preprocessor/package.xml index 3eea0f3e2eb9a..557e835a247e9 100644 --- a/sensing/pointcloud_preprocessor/package.xml +++ b/sensing/autoware_pointcloud_preprocessor/package.xml @@ -1,9 +1,9 @@ - pointcloud_preprocessor + autoware_pointcloud_preprocessor 0.1.0 - The ROS 2 pointcloud_preprocessor package + The ROS 2 autoware_pointcloud_preprocessor package amc-nu Yukihiro Saito Shunsuke Miura diff --git a/sensing/pointcloud_preprocessor/schema/distortion_corrector_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json similarity index 100% rename from sensing/pointcloud_preprocessor/schema/distortion_corrector_node.schema.json rename to sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json diff --git a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp similarity index 98% rename from sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp index aae50a18f2024..de570f354393f 100644 --- a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp" #include "autoware_point_types/types.hpp" #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using autoware_point_types::PointXYZIRCAEDT; using diagnostic_msgs::msg::DiagnosticStatus; @@ -462,7 +462,7 @@ rcl_interfaces::msg::SetParametersResult BlockageDiagComponent::paramCallback( result.reason = "success"; return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::BlockageDiagComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::BlockageDiagComponent) diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp similarity index 98% rename from sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index d13f8a12b2327..95c353212484c 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -49,9 +49,9 @@ * */ -#include "pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp" -#include "pointcloud_preprocessor/utility/memory.hpp" +#include "autoware/pointcloud_preprocessor/utility/memory.hpp" #include @@ -68,7 +68,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////// -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchronizerComponent( const rclcpp::NodeOptions & node_options) @@ -728,8 +728,8 @@ void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus( : "Some topics are not concatenated"; stat.summary(level, message); } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include RCLCPP_COMPONENTS_REGISTER_NODE( - pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent) + autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent) diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp similarity index 98% rename from sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp rename to sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp index 3255df4b8613c..24c4b572181fe 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp" +#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp" -#include "pointcloud_preprocessor/utility/memory.hpp" +#include "autoware/pointcloud_preprocessor/utility/memory.hpp" #include @@ -31,7 +31,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////// -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { PointCloudConcatenationComponent::PointCloudConcatenationComponent( const rclcpp::NodeOptions & node_options) @@ -504,7 +504,7 @@ void PointCloudConcatenationComponent::checkConcatStatus( : "Some topics are not concatenated"; stat.summary(level, message); } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::PointCloudConcatenationComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::PointCloudConcatenationComponent) diff --git a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp similarity index 97% rename from sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp index a56d8f1570234..a09b6bfb6a1ce 100644 --- a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp @@ -49,13 +49,13 @@ * */ -#include "pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_nodelet.hpp" #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { CropBoxFilterComponent::CropBoxFilterComponent(const rclcpp::NodeOptions & options) : Filter("CropBoxFilter", options) @@ -296,7 +296,7 @@ rcl_interfaces::msg::SetParametersResult CropBoxFilterComponent::paramCallback( return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::CropBoxFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::CropBoxFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp similarity index 98% rename from sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp rename to sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index 4a7152a3cd38a..652edd9126358 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" +#include "autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" -#include "pointcloud_preprocessor/utility/memory.hpp" +#include "autoware/pointcloud_preprocessor/utility/memory.hpp" #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { template @@ -463,4 +463,4 @@ inline void DistortionCorrector3D::undistortPointImplementation( prev_transformation_matrix_ = transformation_matrix_; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp similarity index 92% rename from sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp rename to sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp index b5cf581301a23..822bb2ba5add5 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp" +#include "autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp" -#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" +#include "autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { /** @brief Constructor. */ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOptions & options) @@ -118,7 +118,7 @@ void DistortionCorrectorComponent::onPointCloud(PointCloud2::UniquePtr pointclou } } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::DistortionCorrectorComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::DistortionCorrectorComponent) diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp similarity index 93% rename from sensing/pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp index 6a9a5818b19ce..a4ccca9beea72 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/approximate_downsample_filter_nodelet.cpp @@ -49,7 +49,7 @@ * */ -#include "pointcloud_preprocessor/downsample_filter/approximate_downsample_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/downsample_filter/approximate_downsample_filter_nodelet.hpp" #include #include @@ -57,7 +57,7 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { ApproximateDownsampleFilterComponent::ApproximateDownsampleFilterComponent( const rclcpp::NodeOptions & options) @@ -117,7 +117,8 @@ rcl_interfaces::msg::SetParametersResult ApproximateDownsampleFilterComponent::p return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::ApproximateDownsampleFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::pointcloud_preprocessor::ApproximateDownsampleFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp similarity index 97% rename from sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp rename to sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp index b9488d1ed7a73..c0e41239057f0 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp" +#include "autoware/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp" -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { FasterVoxelGridDownsampleFilter::FasterVoxelGridDownsampleFilter() @@ -195,4 +195,4 @@ void FasterVoxelGridDownsampleFilter::copy_centroids_to_output( } } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp similarity index 96% rename from sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp rename to sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp index 83c9058fd5fa5..834f9b8d8fbc0 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp" +#include "autoware/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp" #include "robin_hood.h" @@ -49,7 +49,7 @@ struct VoxelKeyEqual }; } // namespace -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { PickupBasedVoxelGridDownsampleFilterComponent::PickupBasedVoxelGridDownsampleFilterComponent( const rclcpp::NodeOptions & options) @@ -186,8 +186,8 @@ PickupBasedVoxelGridDownsampleFilterComponent::paramCallback( return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include RCLCPP_COMPONENTS_REGISTER_NODE( - pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent) + autoware::pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp similarity index 93% rename from sensing/pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp index 6216b1dad97e8..32abafb759b73 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/random_downsample_filter_nodelet.cpp @@ -46,11 +46,11 @@ * */ -#include "pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp" #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { RandomDownsampleFilterComponent::RandomDownsampleFilterComponent( const rclcpp::NodeOptions & options) @@ -103,6 +103,6 @@ rcl_interfaces::msg::SetParametersResult RandomDownsampleFilterComponent::paramC return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::RandomDownsampleFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::RandomDownsampleFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/robin_hood.h b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h similarity index 100% rename from sensing/pointcloud_preprocessor/src/downsample_filter/robin_hood.h rename to sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp similarity index 93% rename from sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp index 6e7469ff05f67..7f8c500d40f45 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp @@ -48,9 +48,9 @@ * */ -#include "pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_nodelet.hpp" -#include "pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp" +#include "autoware/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp" #include #include @@ -58,7 +58,7 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { VoxelGridDownsampleFilterComponent::VoxelGridDownsampleFilterComponent( const rclcpp::NodeOptions & options) @@ -133,7 +133,8 @@ rcl_interfaces::msg::SetParametersResult VoxelGridDownsampleFilterComponent::par return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::VoxelGridDownsampleFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::pointcloud_preprocessor::VoxelGridDownsampleFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp similarity index 94% rename from sensing/pointcloud_preprocessor/src/filter.cpp rename to sensing/autoware_pointcloud_preprocessor/src/filter.cpp index 435cecec8b6f2..95e85f8450840 100644 --- a/sensing/pointcloud_preprocessor/src/filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp @@ -49,9 +49,9 @@ * */ -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/utility/memory.hpp" +#include "autoware/pointcloud_preprocessor/utility/memory.hpp" #include @@ -64,7 +64,7 @@ #include ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -pointcloud_preprocessor::Filter::Filter( +autoware::pointcloud_preprocessor::Filter::Filter( const std::string & filter_name, const rclcpp::NodeOptions & options) : Node(filter_name, options), filter_field_name_(filter_name) { @@ -112,20 +112,20 @@ pointcloud_preprocessor::Filter::Filter( } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -void pointcloud_preprocessor::Filter::setupTF() +void autoware::pointcloud_preprocessor::Filter::setupTF() { tf_buffer_ = std::make_shared(this->get_clock()); tf_listener_ = std::make_shared(*tf_buffer_); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -void pointcloud_preprocessor::Filter::subscribe() +void autoware::pointcloud_preprocessor::Filter::subscribe() { std::string filter_name = ""; subscribe(filter_name); } -void pointcloud_preprocessor::Filter::subscribe(const std::string & filter_name) +void autoware::pointcloud_preprocessor::Filter::subscribe(const std::string & filter_name) { // TODO(sykwer): Change the corresponding node to subscribe to `faster_input_indices_callback` // each time a child class supports the faster version. @@ -165,7 +165,7 @@ void pointcloud_preprocessor::Filter::subscribe(const std::string & filter_name) } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -void pointcloud_preprocessor::Filter::unsubscribe() +void autoware::pointcloud_preprocessor::Filter::unsubscribe() { if (use_indices_) { sub_input_filter_.unsubscribe(); @@ -183,7 +183,7 @@ void pointcloud_preprocessor::Filter::unsubscribe() ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// // TODO(sykwer): Temporary Implementation: Delete this function definition when all the filter nodes // conform to new API. -void pointcloud_preprocessor::Filter::computePublish( +void autoware::pointcloud_preprocessor::Filter::computePublish( const PointCloud2ConstPtr & input, const IndicesPtr & indices) { auto output = std::make_unique(); @@ -202,7 +202,8 @@ void pointcloud_preprocessor::Filter::computePublish( } ////////////////////////////////////////////////////////////////////////////////////////////// -rcl_interfaces::msg::SetParametersResult pointcloud_preprocessor::Filter::filterParamCallback( +rcl_interfaces::msg::SetParametersResult +autoware::pointcloud_preprocessor::Filter::filterParamCallback( const std::vector & p) { std::scoped_lock lock(mutex_); @@ -224,7 +225,7 @@ rcl_interfaces::msg::SetParametersResult pointcloud_preprocessor::Filter::filter ////////////////////////////////////////////////////////////////////////////////////////////// // TODO(sykwer): Temporary Implementation: Delete this function definition when all the filter nodes // conform to new API. -void pointcloud_preprocessor::Filter::input_indices_callback( +void autoware::pointcloud_preprocessor::Filter::input_indices_callback( const PointCloud2ConstPtr cloud, const PointIndicesConstPtr indices) { // If cloud is given, check if it's valid @@ -301,7 +302,7 @@ void pointcloud_preprocessor::Filter::input_indices_callback( // For performance reason, we get only a transformation matrix here. // The implementation is based on the one shown in the URL below. // https://github.com/ros-perception/perception_pcl/blob/628aaec1dc73ef4adea01e9d28f11eb417b948fd/pcl_ros/src/transforms.cpp#L61-L94 -bool pointcloud_preprocessor::Filter::_calculate_transform_matrix( +bool autoware::pointcloud_preprocessor::Filter::_calculate_transform_matrix( const std::string & target_frame, const sensor_msgs::msg::PointCloud2 & from, const tf2_ros::Buffer & tf_buffer, Eigen::Matrix4f & eigen_transform /*output*/) { @@ -328,7 +329,7 @@ bool pointcloud_preprocessor::Filter::_calculate_transform_matrix( } // Returns false in error cases -bool pointcloud_preprocessor::Filter::calculate_transform_matrix( +bool autoware::pointcloud_preprocessor::Filter::calculate_transform_matrix( const std::string & target_frame, const sensor_msgs::msg::PointCloud2 & from, TransformInfo & transform_info /*output*/) { @@ -362,7 +363,8 @@ bool pointcloud_preprocessor::Filter::calculate_transform_matrix( } // Returns false in error cases -bool pointcloud_preprocessor::Filter::convert_output_costly(std::unique_ptr & output) +bool autoware::pointcloud_preprocessor::Filter::convert_output_costly( + std::unique_ptr & output) { // In terms of performance, we should avoid using pcl_ros library function, // but this code path isn't reached in the main use case of Autoware, so it's left as is for now. @@ -410,7 +412,7 @@ bool pointcloud_preprocessor::Filter::convert_output_costly(std::unique_ptr #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using autoware_point_types::PointXYZIRCAEDT; using autoware_point_types::ReturnType; @@ -374,7 +374,7 @@ rcl_interfaces::msg::SetParametersResult DualReturnOutlierFilterComponent::param return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::DualReturnOutlierFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::DualReturnOutlierFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp similarity index 91% rename from sensing/pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp index bbf01e0bdf223..05bf3898d0cf0 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp" #include #include @@ -20,7 +20,7 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { RadiusSearch2DOutlierFilterComponent::RadiusSearch2DOutlierFilterComponent( const rclcpp::NodeOptions & options) @@ -88,7 +88,8 @@ rcl_interfaces::msg::SetParametersResult RadiusSearch2DOutlierFilterComponent::p return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::RadiusSearch2DOutlierFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::pointcloud_preprocessor::RadiusSearch2DOutlierFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp similarity index 98% rename from sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index 5e783f1e07418..f8024b7bd116b 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp" #include "autoware_point_types/types.hpp" @@ -20,7 +20,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { using autoware_point_types::PointXYZIRADRT; @@ -419,7 +419,7 @@ float RingOutlierFilterComponent::calculateVisibilityScore( return 1.0f - num_filled_pixels; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::RingOutlierFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::RingOutlierFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp similarity index 92% rename from sensing/pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp index 8745c20a7cb0b..94dabf7ee5d9b 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_nodelet.hpp" #include #include @@ -20,7 +20,7 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { VoxelGridOutlierFilterComponent::VoxelGridOutlierFilterComponent( const rclcpp::NodeOptions & options) @@ -93,7 +93,7 @@ rcl_interfaces::msg::SetParametersResult VoxelGridOutlierFilterComponent::paramC return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::VoxelGridOutlierFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::VoxelGridOutlierFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp similarity index 92% rename from sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp index 6011c92afaeb0..53bb6ad619333 100644 --- a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp @@ -48,7 +48,7 @@ * */ -#include "pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp" #include #include @@ -56,7 +56,7 @@ #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { PassThroughFilterComponent::PassThroughFilterComponent(const rclcpp::NodeOptions & options) : Filter("PassThroughFilter", options) @@ -89,7 +89,7 @@ rcl_interfaces::msg::SetParametersResult PassThroughFilterComponent::paramCallba return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::PassThroughFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::PassThroughFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp similarity index 93% rename from sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp index 130e3e3de7934..cc9f3276033a1 100644 --- a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp" #include #include @@ -21,7 +21,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { PassThroughFilterUInt16Component::PassThroughFilterUInt16Component( const rclcpp::NodeOptions & options) @@ -121,7 +121,7 @@ rcl_interfaces::msg::SetParametersResult PassThroughFilterUInt16Component::param return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::PassThroughFilterUInt16Component) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::PassThroughFilterUInt16Component) diff --git a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp similarity index 99% rename from sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp rename to sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp index d68ba32282351..c42abd27fe9c8 100644 --- a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp @@ -51,7 +51,7 @@ * */ -#include "pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp" +#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp" ////////////////////////////////////////////////////////////////////////// void pcl::PassThroughUInt16::applyFilter(PCLPointCloud2 & output) diff --git a/sensing/pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp similarity index 90% rename from sensing/pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp index cfaffece4169f..9502add4b38ce 100644 --- a/sensing/pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp" #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { PointcloudAccumulatorComponent::PointcloudAccumulatorComponent(const rclcpp::NodeOptions & options) : Filter("PointcloudAccumulator", options) @@ -75,7 +75,7 @@ rcl_interfaces::msg::SetParametersResult PointcloudAccumulatorComponent::paramCa return result; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::PointcloudAccumulatorComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::PointcloudAccumulatorComponent) diff --git a/sensing/pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp b/sensing/autoware_pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp similarity index 91% rename from sensing/pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp rename to sensing/autoware_pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp index 6cdfc8bbe2c05..71b4c2026396e 100644 --- a/sensing/pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/polygon_remover/polygon_remover.hpp" +#include "autoware/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp" -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { PolygonRemoverComponent::PolygonRemoverComponent(const rclcpp::NodeOptions & options) : Filter("PolygonRemover", options) @@ -70,7 +70,7 @@ void PolygonRemoverComponent::filter( void PolygonRemoverComponent::update_polygon( const geometry_msgs::msg::Polygon::ConstSharedPtr & polygon_in) { - pointcloud_preprocessor::utils::to_cgal_polygon(*polygon_in, polygon_cgal_); + autoware::pointcloud_preprocessor::utils::to_cgal_polygon(*polygon_in, polygon_cgal_); if (will_visualize_) { marker_.ns = ""; marker_.id = 0; @@ -132,11 +132,11 @@ sensor_msgs::msg::PointCloud2 PolygonRemoverComponent::remove_updated_polygon_fr } PointCloud2 cloud_out; - pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( + autoware::pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( *cloud_in, polygon_cgal_, cloud_out); return cloud_out; } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::PolygonRemoverComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::PolygonRemoverComponent) diff --git a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp similarity index 98% rename from sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp index 11b1268b5ac16..edbe30f8f0ea7 100644 --- a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp @@ -21,7 +21,7 @@ * @author Yoshi Ri */ -#include "pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp" #include @@ -37,7 +37,7 @@ #define DEFAULT_SYNC_TOPIC_POSTFIX "_synchronized" ////////////////////////////////////////////////////////////////////////////////////////////// -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( const rclcpp::NodeOptions & node_options) @@ -648,7 +648,8 @@ void PointCloudDataSynchronizerComponent::checkSyncStatus( : "Some topics are not concatenated"; stat.summary(level, message); } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::PointCloudDataSynchronizerComponent) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::pointcloud_preprocessor::PointCloudDataSynchronizerComponent) diff --git a/sensing/pointcloud_preprocessor/src/utility/geometry.cpp b/sensing/autoware_pointcloud_preprocessor/src/utility/geometry.cpp similarity index 96% rename from sensing/pointcloud_preprocessor/src/utility/geometry.cpp rename to sensing/autoware_pointcloud_preprocessor/src/utility/geometry.cpp index e3013d05d925f..7e9604c3dd305 100644 --- a/sensing/pointcloud_preprocessor/src/utility/geometry.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/utility/geometry.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/utility/geometry.hpp" +#include "autoware/pointcloud_preprocessor/utility/geometry.hpp" -namespace pointcloud_preprocessor::utils +namespace autoware::pointcloud_preprocessor::utils { void to_cgal_polygon(const geometry_msgs::msg::Polygon & polygon_in, PolygonCgal & polygon_out) { @@ -155,4 +155,4 @@ bool point_within_cgal_polys( return false; } -} // namespace pointcloud_preprocessor::utils +} // namespace autoware::pointcloud_preprocessor::utils diff --git a/sensing/pointcloud_preprocessor/src/utility/memory.cpp b/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp similarity index 98% rename from sensing/pointcloud_preprocessor/src/utility/memory.cpp rename to sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp index 138573a2014ff..7e265bcfb4960 100644 --- a/sensing/pointcloud_preprocessor/src/utility/memory.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/utility/memory.hpp" +#include "autoware/pointcloud_preprocessor/utility/memory.hpp" #include -namespace pointcloud_preprocessor::utils +namespace autoware::pointcloud_preprocessor::utils { bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointCloud2 & input) { @@ -208,4 +208,4 @@ bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::Poi return same_layout; } -} // namespace pointcloud_preprocessor::utils +} // namespace autoware::pointcloud_preprocessor::utils diff --git a/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp similarity index 96% rename from sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp index 9049f2964a850..b6de8bb87d5b1 100644 --- a/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp" -#include "pointcloud_preprocessor/filter.hpp" +#include "autoware/pointcloud_preprocessor/filter.hpp" #include @@ -30,7 +30,7 @@ #include #include -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { Lanelet2MapFilterComponent::Lanelet2MapFilterComponent(const rclcpp::NodeOptions & node_options) : Node("LaneletMapFilter", node_options) @@ -269,7 +269,7 @@ void Lanelet2MapFilterComponent::mapCallback( road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets); } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::Lanelet2MapFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pointcloud_preprocessor::Lanelet2MapFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp similarity index 91% rename from sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp rename to sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp index def7652848642..6272fe30e47c0 100644 --- a/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp" +#include "autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp" namespace { @@ -48,12 +48,12 @@ pcl::PointCloud removePointsWithinPolygons( for (const auto & polygon : polygons) { const auto lanelet_poly = lanelet::utils::to2D(polygon).basicPolygon(); PolygonCgal cgal_poly; - pointcloud_preprocessor::utils::to_cgal_polygon(lanelet_poly, cgal_poly); + autoware::pointcloud_preprocessor::utils::to_cgal_polygon(lanelet_poly, cgal_poly); cgal_polys.emplace_back(cgal_poly); } pcl::PointCloud filtered_cloud; - pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( + autoware::pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( *cloud_in, cgal_polys, filtered_cloud, z_threshold_); return filtered_cloud; @@ -61,7 +61,7 @@ pcl::PointCloud removePointsWithinPolygons( } // anonymous namespace -namespace pointcloud_preprocessor +namespace autoware::pointcloud_preprocessor { VectorMapInsideAreaFilterComponent::VectorMapInsideAreaFilterComponent( const rclcpp::NodeOptions & node_options) @@ -139,7 +139,8 @@ void VectorMapInsideAreaFilterComponent::mapCallback( polygon_lanelets_ = lanelet::utils::query::getAllPolygonsByType(lanelet_map_ptr, polygon_type_); } -} // namespace pointcloud_preprocessor +} // namespace autoware::pointcloud_preprocessor #include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::VectorMapInsideAreaFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::pointcloud_preprocessor::VectorMapInsideAreaFilterComponent) diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp similarity index 98% rename from sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp rename to sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp index 3b500bfb3e982..f90314a001105 100644 --- a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -25,8 +25,8 @@ // imu (6msgs): // 10.09, 10.117, 10.144, 10.171, 10.198, 10.225 +#include "autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" #include "autoware/universe_utils/math/trigonometry.hpp" -#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" #include @@ -48,9 +48,9 @@ class DistortionCorrectorTest : public ::testing::Test { node_ = std::make_shared("test_node"); distortion_corrector_2d_ = - std::make_shared(node_.get()); + std::make_shared(node_.get()); distortion_corrector_3d_ = - std::make_shared(node_.get()); + std::make_shared(node_.get()); // Setup TF tf_broadcaster_ = std::make_shared(node_); @@ -246,8 +246,10 @@ class DistortionCorrectorTest : public ::testing::Test } std::shared_ptr node_; - std::shared_ptr distortion_corrector_2d_; - std::shared_ptr distortion_corrector_3d_; + std::shared_ptr + distortion_corrector_2d_; + std::shared_ptr + distortion_corrector_3d_; std::shared_ptr tf_broadcaster_; static constexpr float standard_tolerance_{1e-4}; diff --git a/sensing/pointcloud_preprocessor/test/test_utilities.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_utilities.cpp similarity index 89% rename from sensing/pointcloud_preprocessor/test/test_utilities.cpp rename to sensing/autoware_pointcloud_preprocessor/test/test_utilities.cpp index e3075b4b11e79..f99901896dfb6 100644 --- a/sensing/pointcloud_preprocessor/test/test_utilities.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_utilities.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/utility/geometry.hpp" +#include "autoware/pointcloud_preprocessor/utility/geometry.hpp" #include @@ -58,7 +58,8 @@ TEST_F(RemovePolygonCgalFromCloudTest, PointsInsidePolygonAreRemoved) sensor_msgs::msg::PointCloud2 cloud_in; CreatePointCloud2(cloud_in, 0.5, 0.5, 0.1); // point inside the polygon - pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud(cloud_in, polygon, cloud_out); + autoware::pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( + cloud_in, polygon, cloud_out); pcl::PointCloud pcl_output; pcl::fromROSMsg(cloud_out, pcl_output); @@ -72,7 +73,8 @@ TEST_F(RemovePolygonCgalFromCloudTest, PointsOutsidePolygonRemain) sensor_msgs::msg::PointCloud2 cloud_in; CreatePointCloud2(cloud_in, 1.5, 1.5, 0.1); // point outside the polygon - pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud(cloud_in, polygon, cloud_out); + autoware::pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( + cloud_in, polygon, cloud_out); pcl::PointCloud pcl_output; pcl::fromROSMsg(cloud_out, pcl_output); @@ -90,7 +92,7 @@ TEST_F(RemovePolygonCgalFromCloudTest, PointsBelowMaxZAreRemoved) CreatePointCloud2(cloud_in, 0.5, 0.5, 0.1); // point inside the polygon, below max_z std::optional max_z = 1.0f; - pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( + autoware::pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( cloud_in, polygon, cloud_out, max_z); pcl::PointCloud pcl_output; @@ -106,7 +108,7 @@ TEST_F(RemovePolygonCgalFromCloudTest, PointsAboveMaxZRemain) CreatePointCloud2(cloud_in, 0.5, 0.5, 1.5); // point inside the polygon, above max_z std::optional max_z = 1.0f; - pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( + autoware::pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud( cloud_in, polygon, cloud_out, max_z); pcl::PointCloud pcl_output;