Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(euclidean_cluster): reduce false negative #815

Merged
merged 2 commits into from
Sep 11, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@
<arg name="image_number" default="1" description="choose image raw number(1-8)"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `pointpainting`, `clustering`"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_downsample_pointcloud" default="true" description="use downsample pointcloud in perception"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_pointcloud_container" default="false" description="use pointcloud container for detection preprocessor"/>
<arg name="container_name" default="pointcloud_container"/>
Expand Down Expand Up @@ -74,7 +73,6 @@
<arg name="input_pointcloud" value="$(var clustering/input/pointcloud)"/>
<arg name="output_clusters" value="clusters"/>
<arg name="use_pointcloud_map" value="false"/>
<arg name="use_downsample_pointcloud" value="$(var use_downsample_pointcloud)"/>
</include>
</group>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
<arg name="input/pointcloud"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `clustering`"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_downsample_pointcloud" default="true" description="use downsample pointcloud in perception"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_pointcloud_container" default="false" description="use pointcloud container for detection preprocessor"/>
<arg name="container_name" default="pointcloud_container"/>
Expand Down Expand Up @@ -60,7 +59,6 @@
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="score_threshold" value="$(var score_threshold)"/>
<arg name="use_downsample_pointcloud" value="$(var use_downsample_pointcloud)"/>
</include>
</group>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
<arg name="output/objects" default="objects"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `clustering`"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_downsample_pointcloud" default="true" description="use downsample pointcloud in perception"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_pointcloud_container" default="false" description="use pointcloud container for detection preprocessor"/>
<arg name="container_name" default="pointcloud_container"/>
Expand Down Expand Up @@ -34,7 +33,6 @@
<arg name="input_pointcloud" value="$(var clustering/input/pointcloud)"/>
<arg name="output_clusters" value="clusters"/>
<arg name="use_pointcloud_map" value="false"/>
<arg name="use_downsample_pointcloud" value="$(var use_downsample_pointcloud)"/>
</include>
</group>

Expand Down
2 changes: 0 additions & 2 deletions launch/tier4_perception_launch/launch/perception.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@
<arg name="image_number" default="6" description="choose image raw number(1-8)"/>
<arg name="use_vector_map" default="true" description="use vector map in prediction"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_downsample_pointcloud" default="false" description="use downsample pointcloud in perception"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg
name="use_empty_dynamic_object_publisher"
Expand Down Expand Up @@ -146,7 +145,6 @@
<arg name="voxel_grid_param_path" value="$(var object_recognition_detection_voxel_grid_based_euclidean_param_path)"/>
<arg name="voxel_grid_based_euclidean_param_path" value="$(var object_recognition_detection_voxel_grid_based_euclidean_cluster_param_path)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_downsample_pointcloud" value="$(var use_downsample_pointcloud)"/>
<arg name="use_object_filter" value="$(var use_object_filter)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,9 @@
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.conditions import IfCondition
from launch.substitutions import AndSubstitution
from launch.conditions import UnlessCondition
from launch.substitutions import AnonName
from launch.substitutions import LaunchConfiguration
from launch.substitutions import NotSubstitution
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
Expand Down Expand Up @@ -165,7 +164,7 @@ def load_composable_node_param(param_path):
)

# set euclidean cluster as a component
use_downsample_euclidean_cluster_component = ComposableNode(
euclidean_cluster_component = ComposableNode(
package=pkg,
namespace=ns,
plugin="euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
Expand All @@ -177,108 +176,40 @@ def load_composable_node_param(param_path):
parameters=[load_composable_node_param("voxel_grid_based_euclidean_param_path")],
)

use_map_disuse_downsample_euclidean_component = ComposableNode(
package=pkg,
namespace=ns,
plugin="euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
name="euclidean_cluster",
remappings=[
("input", "map_filter/pointcloud"),
("output", LaunchConfiguration("output_clusters")),
],
parameters=[load_composable_node_param("voxel_grid_based_euclidean_param_path")],
)
disuse_map_disuse_downsample_euclidean_component = ComposableNode(
package=pkg,
namespace=ns,
plugin="euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
name="euclidean_cluster",
remappings=[
("input", LaunchConfiguration("input_pointcloud")),
("output", LaunchConfiguration("output_clusters")),
],
parameters=[load_composable_node_param("voxel_grid_based_euclidean_param_path")],
)

container = ComposableNodeContainer(
name="euclidean_cluster_container",
package="rclcpp_components",
namespace=ns,
executable="component_container",
composable_node_descriptions=[],
composable_node_descriptions=[
voxel_grid_filter_component,
outlier_filter_component,
downsample_concat_component,
euclidean_cluster_component,
],
output="screen",
)

use_map_use_downsample_loader = LoadComposableNodes(
use_map_loader = LoadComposableNodes(
composable_node_descriptions=[
compare_map_filter_component,
use_map_short_range_crop_box_filter_component,
use_map_long_range_crop_box_filter_component,
voxel_grid_filter_component,
outlier_filter_component,
downsample_concat_component,
use_downsample_euclidean_cluster_component,
],
target_container=container,
condition=IfCondition(
AndSubstitution(
LaunchConfiguration("use_pointcloud_map"),
LaunchConfiguration("use_downsample_pointcloud"),
)
),
condition=IfCondition(LaunchConfiguration("use_pointcloud_map")),
)

disuse_map_use_downsample_loader = LoadComposableNodes(
disuse_map_loader = LoadComposableNodes(
composable_node_descriptions=[
disuse_map_short_range_crop_box_filter_component,
disuse_map_long_range_crop_box_filter_component,
voxel_grid_filter_component,
outlier_filter_component,
downsample_concat_component,
use_downsample_euclidean_cluster_component,
],
target_container=container,
condition=IfCondition(
AndSubstitution(
NotSubstitution(LaunchConfiguration("use_pointcloud_map")),
LaunchConfiguration("use_downsample_pointcloud"),
)
),
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_map")),
)

use_map_disuse_downsample_loader = LoadComposableNodes(
composable_node_descriptions=[
compare_map_filter_component,
use_map_disuse_downsample_euclidean_component,
],
target_container=container,
condition=IfCondition(
AndSubstitution(
(LaunchConfiguration("use_pointcloud_map")),
NotSubstitution(LaunchConfiguration("use_downsample_pointcloud")),
)
),
)

disuse_map_disuse_downsample_loader = LoadComposableNodes(
composable_node_descriptions=[
disuse_map_disuse_downsample_euclidean_component,
],
target_container=container,
condition=IfCondition(
AndSubstitution(
NotSubstitution(LaunchConfiguration("use_pointcloud_map")),
NotSubstitution(LaunchConfiguration("use_downsample_pointcloud")),
)
),
)
return [
container,
use_map_use_downsample_loader,
disuse_map_use_downsample_loader,
use_map_disuse_downsample_loader,
disuse_map_disuse_downsample_loader,
]
return [container, use_map_loader, disuse_map_loader]


def generate_launch_description():
Expand All @@ -291,7 +222,6 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("input_map", "/map/pointcloud_map"),
add_launch_arg("output_clusters", "clusters"),
add_launch_arg("use_pointcloud_map", "false"),
add_launch_arg("use_downsample_pointcloud", "false"),
add_launch_arg(
"voxel_grid_param_path",
[
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
<arg name="input_map" default="/map/pointcloud_map"/>
<arg name="output_clusters" default="clusters"/>
<arg name="use_pointcloud_map" default="false"/>
<arg name="use_downsample_pointcloud" default="false"/>
<arg name="voxel_grid_param_path" default="$(find-pkg-share euclidean_cluster)/config/voxel_grid.param.yaml"/>
<arg name="compare_map_param_path" default="$(find-pkg-share euclidean_cluster)/config/compare_map.param.yaml"/>
<arg name="outlier_param_path" default="$(find-pkg-share euclidean_cluster)/config/outlier.param.yaml"/>
Expand All @@ -15,7 +14,6 @@
<arg name="input_map" value="$(var input_map)"/>
<arg name="output_clusters" value="$(var output_clusters)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_downsample_pointcloud" value="$(var use_downsample_pointcloud)"/>
<arg name="voxel_grid_param_path" value="$(var voxel_grid_param_path)"/>
<arg name="compare_map_param_path" value="$(var compare_map_param_path)"/>
<arg name="outlier_param_path" value="$(var outlier_param_path)"/>
Expand Down
23 changes: 0 additions & 23 deletions sensing/pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,21 +41,6 @@ ament_target_dependencies(pointcloud_preprocessor_filter_base
pcl_ros
)

add_library(faster_voxel_grid_downsample_filter SHARED
src/downsample_filter/faster_voxel_grid_downsample_filter.cpp
)

target_include_directories(faster_voxel_grid_downsample_filter PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)

ament_target_dependencies(faster_voxel_grid_downsample_filter
pcl_conversions
rclcpp
sensor_msgs
)

ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/utility/utilities.cpp
src/concatenate_data/concatenate_and_time_sync_nodelet.cpp
Expand All @@ -82,7 +67,6 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED

target_link_libraries(pointcloud_preprocessor_filter
pointcloud_preprocessor_filter_base
faster_voxel_grid_downsample_filter
${Boost_LIBRARIES}
${OpenCV_LIBRARIES}
${PCL_LIBRARIES}
Expand Down Expand Up @@ -195,13 +179,6 @@ install(
RUNTIME DESTINATION bin
)

install(
TARGETS faster_voxel_grid_downsample_filter EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(
DIRECTORY include/
DESTINATION include/${PROJECT_NAME}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@
#define POINTCLOUD_PREPROCESSOR__CROP_BOX_FILTER__CROP_BOX_FILTER_NODELET_HPP_

#include "pointcloud_preprocessor/filter.hpp"
#include "pointcloud_preprocessor/transform_info.hpp"

#include <geometry_msgs/msg/polygon_stamped.hpp>

Expand Down

This file was deleted.

Loading
Loading