Skip to content

Commit

Permalink
refactor(pointcloud_preprocessor): prefix package and namespace with …
Browse files Browse the repository at this point in the history
…autoware (autowarefoundation#7983)

* refactor(pointcloud_preprocessor)!: prefix package and namespace with autoware

Signed-off-by: Amadeusz Szymko <[email protected]>

* style(pre-commit): autofix

* style(pointcloud_preprocessor): suppress line length check for macros

Signed-off-by: Amadeusz Szymko <[email protected]>

* fix(pointcloud_preprocessor): missing prefix

Signed-off-by: Amadeusz Szymko <[email protected]>

* fix(pointcloud_preprocessor): missing prefix

Signed-off-by: Amadeusz Szymko <[email protected]>

* fix(pointcloud_preprocessor): missing prefix

Signed-off-by: Amadeusz Szymko <[email protected]>

* fix(pointcloud_preprocessor): missing prefix

Signed-off-by: Amadeusz Szymko <[email protected]>

* fix(pointcloud_preprocessor): missing prefix

Signed-off-by: Amadeusz Szymko <[email protected]>

* refactor(pointcloud_preprocessor): directory structure (soft)

Signed-off-by: Amadeusz Szymko <[email protected]>

* refactor(pointcloud_preprocessor): directory structure (hard)

Signed-off-by: Amadeusz Szymko <[email protected]>

---------

Signed-off-by: Amadeusz Szymko <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Kenzo Lobos Tsunekawa <[email protected]>
  • Loading branch information
3 people authored and esteve committed Aug 13, 2024
1 parent 30819f7 commit 29f8568
Show file tree
Hide file tree
Showing 134 changed files with 465 additions and 431 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
2 changes: 1 addition & 1 deletion control/autoware_autonomous_emergency_braking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<depend>autoware_control_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_pointcloud_preprocessor</depend>
<depend>autoware_system_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_info_utils</depend>
Expand All @@ -27,7 +28,6 @@
<depend>nav_msgs</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>pointcloud_preprocessor</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
Expand Down
6 changes: 3 additions & 3 deletions launch/tier4_localization_launch/launch/util/util.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,21 +9,21 @@
<arg name="use_intra_process" default="true" description="use ROS 2 component container communication"/>

<load_composable_node target="$(var localization_pointcloud_container_name)">
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::CropBoxFilterComponent" name="crop_box_filter_measurement_range">
<composable_node pkg="autoware_pointcloud_preprocessor" plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent" name="crop_box_filter_measurement_range">
<param from="$(var ndt_scan_matcher/pointcloud_preprocessor/crop_box_filter_measurement_range_param_path)"/>
<remap from="input" to="$(var input_pointcloud)"/>
<remap from="output" to="measurement_range/pointcloud"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>

<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent" name="voxel_grid_downsample_filter">
<composable_node pkg="autoware_pointcloud_preprocessor" plugin="autoware::pointcloud_preprocessor::VoxelGridDownsampleFilterComponent" name="voxel_grid_downsample_filter">
<param from="$(var ndt_scan_matcher/pointcloud_preprocessor/voxel_grid_downsample_filter_param_path)"/>
<remap from="input" to="measurement_range/pointcloud"/>
<remap from="output" to="voxel_grid_downsample/pointcloud"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>

<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::RandomDownsampleFilterComponent" name="random_downsample_filter">
<composable_node pkg="autoware_pointcloud_preprocessor" plugin="autoware::pointcloud_preprocessor::RandomDownsampleFilterComponent" name="random_downsample_filter">
<param from="$(var ndt_scan_matcher/pointcloud_preprocessor/random_downsample_filter_param_path)"/>
<remap from="input" to="voxel_grid_downsample/pointcloud"/>
<remap from="output" to="$(var output/pointcloud)"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_localization_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,14 @@

<exec_depend>automatic_pose_initializer</exec_depend>
<exec_depend>autoware_ar_tag_based_localizer</exec_depend>
<exec_depend>autoware_pointcloud_preprocessor</exec_depend>
<exec_depend>eagleye_geo_pose_fusion</exec_depend>
<exec_depend>eagleye_gnss_converter</exec_depend>
<exec_depend>eagleye_rt</exec_depend>
<exec_depend>ekf_localizer</exec_depend>
<exec_depend>geo_pose_projector</exec_depend>
<exec_depend>gyro_odometer</exec_depend>
<exec_depend>ndt_scan_matcher</exec_depend>
<exec_depend>pointcloud_preprocessor</exec_depend>
<exec_depend>pose_estimator_arbiter</exec_depend>
<exec_depend>pose_initializer</exec_depend>
<exec_depend>pose_instability_detector</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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")),
Expand All @@ -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")),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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"),
Expand Down Expand Up @@ -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=[
Expand All @@ -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=[
Expand All @@ -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=[
Expand Down Expand Up @@ -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),
Expand Down Expand Up @@ -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=[
Expand All @@ -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=[
Expand All @@ -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"),
Expand All @@ -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"),
Expand Down
7 changes: 6 additions & 1 deletion launch/tier4_perception_launch/launch/perception.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,12 @@
<group if="$(var downsample_perception_common_pointcloud)">
<push-ros-namespace namespace="common"/>
<load_composable_node target="$(var pointcloud_container_name)">
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent" name="pointcloud_downsample_node" namespace="">
<composable_node
pkg="autoware_pointcloud_preprocessor"
plugin="autoware::pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent"
name="pointcloud_downsample_node"
namespace=""
>
<remap from="input" to="$(var input/pointcloud)"/>
<remap from="output" to="$(var downsampled_pointcloud)"/>
<param name="voxel_size_x" value="$(var common_downsample_voxel_size_x)"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_perception_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<exec_depend>autoware_object_merger</exec_depend>
<exec_depend>autoware_object_range_splitter</exec_depend>
<exec_depend>autoware_object_velocity_splitter</exec_depend>
<exec_depend>autoware_pointcloud_preprocessor</exec_depend>
<exec_depend>autoware_radar_crossing_objects_noise_filter</exec_depend>
<exec_depend>autoware_radar_fusion_to_detected_object</exec_depend>
<exec_depend>autoware_radar_object_clustering</exec_depend>
Expand All @@ -37,7 +38,6 @@
<exec_depend>image_transport_decompressor</exec_depend>
<exec_depend>lidar_apollo_instance_segmentation</exec_depend>
<exec_depend>occupancy_grid_map_outlier_filter</exec_depend>
<exec_depend>pointcloud_preprocessor</exec_depend>
<exec_depend>pointcloud_to_laserscan</exec_depend>
<exec_depend>probabilistic_occupancy_grid_map</exec_depend>
<exec_depend>shape_estimation</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>

<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::VectorMapInsideAreaFilterComponent" name="vector_map_inside_area_filter_node" namespace="">
<composable_node pkg="autoware_pointcloud_preprocessor" plugin="autoware::pointcloud_preprocessor::VectorMapInsideAreaFilterComponent" name="vector_map_inside_area_filter_node" namespace="">
<!-- topic remap -->
<remap from="input/vector_map" to="$(var input_vector_map_topic_name)"/>
<remap from="input" to="compare_map_filtered/pointcloud"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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")),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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")),
Expand Down
2 changes: 1 addition & 1 deletion perception/compare_map_segmentation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}
Expand Down
2 changes: 1 addition & 1 deletion perception/compare_map_segmentation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,12 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_map_msgs</depend>
<depend>autoware_pointcloud_preprocessor</depend>
<depend>autoware_universe_utils</depend>
<depend>grid_map_pcl</depend>
<depend>grid_map_ros</depend>
<depend>nav_msgs</depend>
<depend>pcl_conversions</depend>
<depend>pointcloud_preprocessor</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <grid_map_core/GridMap.hpp>
#include <grid_map_cv/grid_map_cv.hpp>
Expand All @@ -31,7 +31,7 @@
#include <vector>
namespace autoware::compare_map_segmentation
{
class CompareElevationMapFilterComponent : public pointcloud_preprocessor::Filter
class CompareElevationMapFilterComponent : public autoware::pointcloud_preprocessor::Filter
{
protected:
void filter(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <pcl/common/point_tests.h> // for pcl::isFinite
#include <pcl/filters/voxel_grid.h>
Expand Down Expand Up @@ -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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <pcl/filters/voxel_grid.h>
#include <pcl/search/pcl_search.h>
Expand Down Expand Up @@ -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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <pcl/filters/voxel_grid.h>
#include <pcl/search/pcl_search.h>
Expand All @@ -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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <pcl/filters/voxel_grid.h>
#include <pcl/search/pcl_search.h>
Expand Down Expand Up @@ -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(
Expand Down
2 changes: 1 addition & 1 deletion perception/ground_segmentation/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
4 changes: 2 additions & 2 deletions perception/ground_segmentation/docs/ransac-ground-filter.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
Loading

0 comments on commit 29f8568

Please sign in to comment.