Skip to content

Commit 4945cd7

Browse files
authored
Merge pull request #189 from eurogroep/feat/ros2-port-all-filters
Feature: ros2 port for all filters
2 parents de3520a + 2fe180c commit 4945cd7

26 files changed

+2178
-265
lines changed

CMakeLists.txt

Lines changed: 33 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ ament_auto_add_executable(generic_laser_filter_node src/generic_laser_filter_nod
4343
##############################################################################
4444

4545
pluginlib_export_plugin_description_file(filters laser_filters_plugins.xml)
46-
ament_auto_package(INSTALL_TO_SHARE examples)
46+
ament_auto_package(INSTALL_TO_SHARE examples test)
4747

4848
##############################################################################
4949
# Test
@@ -77,4 +77,36 @@ if(BUILD_TESTING)
7777
--gtest_output=xml:${RESULT_FILENAME}
7878
RESULT_FILE ${RESULT_FILENAME}
7979
)
80+
81+
set(TEST_NAME test_speckle_filter)
82+
set(RESULT_FILENAME ${AMENT_TEST_RESULTS_DIR}/${PROJECT_NAME}/${TEST_NAME}.gtest.xml)
83+
ament_add_gtest_executable(${TEST_NAME} test/${TEST_NAME}.cpp)
84+
ament_target_dependencies(${TEST_NAME} angles)
85+
target_link_libraries(${TEST_NAME} laser_scan_filters)
86+
ament_add_test(
87+
${TEST_NAME}
88+
COMMAND
89+
$<TARGET_FILE:${TEST_NAME}>
90+
--ros-args
91+
--gtest_output=xml:${RESULT_FILENAME}
92+
RESULT_FILE ${RESULT_FILENAME}
93+
)
94+
95+
set(TEST_NAME test_scan_shadows_filter)
96+
set(RESULT_FILENAME ${AMENT_TEST_RESULTS_DIR}/${PROJECT_NAME}/${TEST_NAME}.gtest.xml)
97+
ament_add_gtest_executable(${TEST_NAME} test/${TEST_NAME}.cpp)
98+
ament_target_dependencies(${TEST_NAME} filters rclcpp sensor_msgs)
99+
target_link_libraries(${TEST_NAME} laser_scan_filters)
100+
ament_add_test(
101+
${TEST_NAME}
102+
COMMAND
103+
$<TARGET_FILE:${TEST_NAME}>
104+
--ros-args
105+
--gtest_output=xml:${RESULT_FILENAME}
106+
RESULT_FILE ${RESULT_FILENAME}
107+
)
108+
109+
find_package(launch_testing_ament_cmake)
110+
add_launch_test(test/test_polygon_filter.test.py)
111+
add_launch_test(test/test_speckle_filter.test.py)
80112
endif()
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
from launch import LaunchDescription
2+
from launch.substitutions import PathJoinSubstitution
3+
from launch_ros.actions import Node
4+
from ament_index_python.packages import get_package_share_directory
5+
6+
7+
def generate_launch_description():
8+
return LaunchDescription(
9+
[
10+
Node(
11+
package="laser_filters",
12+
executable="scan_to_scan_filter_chain",
13+
parameters=[
14+
PathJoinSubstitution(
15+
[get_package_share_directory("laser_filters"), "examples", "polygon_filter_example.yaml"]
16+
)
17+
],
18+
)
19+
]
20+
)

examples/polygon_filter_example.yaml

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
scan_to_scan_filter_chain:
2+
ros__parameters:
3+
filter1:
4+
name: polygon_filter
5+
type: laser_filters/LaserScanPolygonFilter
6+
params:
7+
polygon_frame: base_link
8+
polygon: '[[0.0, 0.0], [0.1, 0.1], [0.1, 0.0], [0.0, -0.1]]'
9+
invert: false
10+
footprint_topic: base_footprint_exclude
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
from launch import LaunchDescription
2+
from launch.substitutions import PathJoinSubstitution
3+
from launch_ros.actions import Node
4+
from ament_index_python.packages import get_package_share_directory
5+
6+
7+
def generate_launch_description():
8+
return LaunchDescription(
9+
[
10+
Node(
11+
package="laser_filters",
12+
executable="scan_to_scan_filter_chain",
13+
parameters=[
14+
PathJoinSubstitution(
15+
[get_package_share_directory("laser_filters"), "examples", "scan_blob_filter_example.yaml"]
16+
)
17+
],
18+
)
19+
]
20+
)
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
scan_to_scan_filter_chain:
2+
ros__parameters:
3+
filter1:
4+
name: scan_blob_filter
5+
type: laser_filters/ScanBlobFilter
6+
params:
7+
max_radius: 0.25 # maximum radius to be considered as blob object
8+
min_points: 6 # min scan points to be considered as blob object
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
from launch import LaunchDescription
2+
from launch.substitutions import PathJoinSubstitution
3+
from launch_ros.actions import Node
4+
from ament_index_python.packages import get_package_share_directory
5+
6+
7+
def generate_launch_description():
8+
return LaunchDescription(
9+
[
10+
Node(
11+
package="laser_filters",
12+
executable="scan_to_scan_filter_chain",
13+
parameters=[
14+
PathJoinSubstitution(
15+
[get_package_share_directory("laser_filters"), "examples", "sector_filter_example.yaml"]
16+
)
17+
],
18+
)
19+
]
20+
)

examples/sector_filter_example.yaml

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
scan_to_scan_filter_chain:
2+
ros__parameters:
3+
filter1:
4+
name: scan_filter
5+
type: laser_filters/LaserScanSectorFilter
6+
params:
7+
angle_min: 2.54 # if not specified defaults to 0.0
8+
angle_max: -2.54 # if not specified defaults to 0.0
9+
range_min: 0.2 # if not specified defaults to 0.0
10+
range_max: 2.0 # if not specified defaults to 100000.0
11+
clear_inside: true # if not specified defaults to true
12+
invert: false # (!clear_inside) if not specified defaults to false

0 commit comments

Comments
 (0)