Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
…into ros2
  • Loading branch information
bely2803 committed Aug 26, 2024
2 parents f7236ba + 830cde2 commit d58b16d
Show file tree
Hide file tree
Showing 30 changed files with 2,384 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()
18 changes: 18 additions & 0 deletions examples/median_spatial_filter.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
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", "median_spatial_filter_example.yaml",
])],
)
])
5 changes: 5 additions & 0 deletions examples/median_spatial_filter.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<launch>
<node name="scan_to_scan_filter_chain" pkg="laser_filters" exec="scan_to_scan_filter_chain" output="screen">
<param from="$(find-pkg-share laser_filters)/examples/median_spatial_filter_example.yaml" />
</node>
</launch>
17 changes: 17 additions & 0 deletions examples/median_spatial_filter_example.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
scan_to_scan_filter_chain:
ros__parameters:
filter1:
name: median_spatial
type: laser_filters/LaserScanMedianSpatialFilter
params:
window_size: 31
filter2:
name: median_filter
type: laser_filters/LaserArrayFilter
params:
range_filter_chain:
filter1:
name: median
type: filters/MultiChannelMedianFilterFloat
params:
number_of_observations: 3
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
157 changes: 157 additions & 0 deletions include/laser_filters/median_spatial_filter.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,157 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2017, laser_filters authors
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/*
\author Yannic Bachmann
*/

#ifndef LASER_SCAN_MEDIAN_SPATIAL_FILTER_H
#define LASER_SCAN_MEDIAN_SPATIAL_FILTER_H

#include "filters/filter_base.hpp"
#include <sensor_msgs/msg/laser_scan.hpp>
#include <algorithm>
#include <vector>
#include <stdexcept>
#include <limits>
#include <cmath>

namespace laser_filters
{

class LaserScanMedianSpatialFilter : public filters::FilterBase<sensor_msgs::msg::LaserScan>
{
private:
int window_size_;

public:

bool configure()
{
getParam("window_size", window_size_);

// Ensure window size is positive
if (window_size_ <= 0)
{
RCLCPP_ERROR(logging_interface_->get_logger(), "Window size must be positive.\n");
return false;
}

// Ensure window size is odd
// If the window_size is even, the current range, which will be modified cannot be centered in the window.
if (window_size_ % 2 == 0)
{
RCLCPP_WARN(logging_interface_->get_logger(), "Window size must be odd. Automatically setting window_size to %d instead of %d.\n", window_size_+1, window_size_);
window_size_ += 1;
}

return true;
}

virtual ~LaserScanMedianSpatialFilter() {}

bool update(const sensor_msgs::msg::LaserScan &input_scan, sensor_msgs::msg::LaserScan &filtered_scan)
{
filtered_scan = input_scan;

int half_window = window_size_ / 2;
std::vector<float> valid_values;
int nan_count = 0;
int neg_inf_count = 0;
int pos_inf_count = 0;

for (size_t current_beam_index = 0; current_beam_index < input_scan.ranges.size(); ++current_beam_index)
{
valid_values.clear();
nan_count = 0;
neg_inf_count = 0;
pos_inf_count = 0;

// Collect points within the window
for (int window_offset = -half_window; window_offset <= half_window; ++window_offset)
{
int index = current_beam_index + window_offset;

if (index >= 0 && index < input_scan.ranges.size())
{
float value = input_scan.ranges[index];

if (std::isnan(value))
{
nan_count++;
}
else if (value == -std::numeric_limits<float>::infinity())
{
neg_inf_count++;
}
else if (value == std::numeric_limits<float>::infinity())
{
pos_inf_count++;
}
else
{
valid_values.push_back(value);
}
}
}

// Determine which set is the largest
// In case of a tie, prioritize valid-values over nan-values over neg-inf-values over pos-inf-values
if (valid_values.size() >= nan_count && valid_values.size() >= neg_inf_count && valid_values.size() >= pos_inf_count)
{
// Sort the valid values and return the median
std::sort(valid_values.begin(), valid_values.end());
filtered_scan.ranges[current_beam_index] = valid_values[valid_values.size() / 2];
}
else if (nan_count >= valid_values.size() && nan_count >= neg_inf_count && nan_count >= pos_inf_count)
{
filtered_scan.ranges[current_beam_index] = std::numeric_limits<float>::quiet_NaN();
}
else if (neg_inf_count >= valid_values.size() && neg_inf_count >= nan_count && neg_inf_count >= pos_inf_count)
{
filtered_scan.ranges[current_beam_index] = -std::numeric_limits<float>::infinity();
}
else if (pos_inf_count >= valid_values.size() && pos_inf_count >= nan_count && pos_inf_count >= neg_inf_count)
{
filtered_scan.ranges[current_beam_index] = std::numeric_limits<float>::infinity();
}
}

return true;
}
};

} // namespace laser_filters

#endif // LASER_SCAN_MEDIAN_SPATIAL_FILTER_H
Loading

0 comments on commit d58b16d

Please sign in to comment.