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