Skip to content

Commit

Permalink
Merge pull request #189 from eurogroep/feat/ros2-port-all-filters
Browse files Browse the repository at this point in the history
Feature: ros2 port for all filters
  • Loading branch information
jonbinney authored Aug 23, 2024
2 parents de3520a + 2fe180c commit 4945cd7
Show file tree
Hide file tree
Showing 26 changed files with 2,178 additions and 265 deletions.
34 changes: 33 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ ament_auto_add_executable(generic_laser_filter_node src/generic_laser_filter_nod
##############################################################################

pluginlib_export_plugin_description_file(filters laser_filters_plugins.xml)
ament_auto_package(INSTALL_TO_SHARE examples)
ament_auto_package(INSTALL_TO_SHARE examples test)

##############################################################################
# Test
Expand Down Expand Up @@ -77,4 +77,36 @@ if(BUILD_TESTING)
--gtest_output=xml:${RESULT_FILENAME}
RESULT_FILE ${RESULT_FILENAME}
)

set(TEST_NAME test_speckle_filter)
set(RESULT_FILENAME ${AMENT_TEST_RESULTS_DIR}/${PROJECT_NAME}/${TEST_NAME}.gtest.xml)
ament_add_gtest_executable(${TEST_NAME} test/${TEST_NAME}.cpp)
ament_target_dependencies(${TEST_NAME} angles)
target_link_libraries(${TEST_NAME} laser_scan_filters)
ament_add_test(
${TEST_NAME}
COMMAND
$<TARGET_FILE:${TEST_NAME}>
--ros-args
--gtest_output=xml:${RESULT_FILENAME}
RESULT_FILE ${RESULT_FILENAME}
)

set(TEST_NAME test_scan_shadows_filter)
set(RESULT_FILENAME ${AMENT_TEST_RESULTS_DIR}/${PROJECT_NAME}/${TEST_NAME}.gtest.xml)
ament_add_gtest_executable(${TEST_NAME} test/${TEST_NAME}.cpp)
ament_target_dependencies(${TEST_NAME} filters rclcpp sensor_msgs)
target_link_libraries(${TEST_NAME} laser_scan_filters)
ament_add_test(
${TEST_NAME}
COMMAND
$<TARGET_FILE:${TEST_NAME}>
--ros-args
--gtest_output=xml:${RESULT_FILENAME}
RESULT_FILE ${RESULT_FILENAME}
)

find_package(launch_testing_ament_cmake)
add_launch_test(test/test_polygon_filter.test.py)
add_launch_test(test/test_speckle_filter.test.py)
endif()
20 changes: 20 additions & 0 deletions examples/polygon_filter_example.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory


def generate_launch_description():
return LaunchDescription(
[
Node(
package="laser_filters",
executable="scan_to_scan_filter_chain",
parameters=[
PathJoinSubstitution(
[get_package_share_directory("laser_filters"), "examples", "polygon_filter_example.yaml"]
)
],
)
]
)
10 changes: 10 additions & 0 deletions examples/polygon_filter_example.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
scan_to_scan_filter_chain:
ros__parameters:
filter1:
name: polygon_filter
type: laser_filters/LaserScanPolygonFilter
params:
polygon_frame: base_link
polygon: '[[0.0, 0.0], [0.1, 0.1], [0.1, 0.0], [0.0, -0.1]]'
invert: false
footprint_topic: base_footprint_exclude
20 changes: 20 additions & 0 deletions examples/scan_blob_filter_example.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory


def generate_launch_description():
return LaunchDescription(
[
Node(
package="laser_filters",
executable="scan_to_scan_filter_chain",
parameters=[
PathJoinSubstitution(
[get_package_share_directory("laser_filters"), "examples", "scan_blob_filter_example.yaml"]
)
],
)
]
)
8 changes: 8 additions & 0 deletions examples/scan_blob_filter_example.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
scan_to_scan_filter_chain:
ros__parameters:
filter1:
name: scan_blob_filter
type: laser_filters/ScanBlobFilter
params:
max_radius: 0.25 # maximum radius to be considered as blob object
min_points: 6 # min scan points to be considered as blob object
20 changes: 20 additions & 0 deletions examples/sector_filter_example.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory


def generate_launch_description():
return LaunchDescription(
[
Node(
package="laser_filters",
executable="scan_to_scan_filter_chain",
parameters=[
PathJoinSubstitution(
[get_package_share_directory("laser_filters"), "examples", "sector_filter_example.yaml"]
)
],
)
]
)
12 changes: 12 additions & 0 deletions examples/sector_filter_example.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
scan_to_scan_filter_chain:
ros__parameters:
filter1:
name: scan_filter
type: laser_filters/LaserScanSectorFilter
params:
angle_min: 2.54 # if not specified defaults to 0.0
angle_max: -2.54 # if not specified defaults to 0.0
range_min: 0.2 # if not specified defaults to 0.0
range_max: 2.0 # if not specified defaults to 100000.0
clear_inside: true # if not specified defaults to true
invert: false # (!clear_inside) if not specified defaults to false
Loading

0 comments on commit 4945cd7

Please sign in to comment.