|
| 1 | +/********************************************************************* |
| 2 | +* Software License Agreement (BSD License) |
| 3 | +* |
| 4 | +* Copyright (c) 2024, Anthony Goeckner <anthony.goeckner@gmail.com> |
| 5 | +* All rights reserved. |
| 6 | +* |
| 7 | +* Redistribution and use in source and binary forms, with or without |
| 8 | +* modification, are permitted provided that the following conditions |
| 9 | +* are met: |
| 10 | +* |
| 11 | +* * Redistributions of source code must retain the above copyright |
| 12 | +* notice, this list of conditions and the following disclaimer. |
| 13 | +* * Redistributions in binary form must reproduce the above |
| 14 | +* copyright notice, this list of conditions and the following |
| 15 | +* disclaimer in the documentation and/or other materials provided |
| 16 | +* with the distribution. |
| 17 | +* * Neither the name of the Willow Garage nor the names of its |
| 18 | +* contributors may be used to endorse or promote products derived |
| 19 | +* from this software without specific prior written permission. |
| 20 | +* |
| 21 | +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
| 22 | +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
| 23 | +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
| 24 | +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
| 25 | +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
| 26 | +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
| 27 | +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; |
| 28 | +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 29 | +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
| 30 | +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
| 31 | +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 32 | +* POSSIBILITY OF SUCH DAMAGE. |
| 33 | +*********************************************************************/ |
| 34 | + |
| 35 | +#ifndef BINNING_FILTER_H |
| 36 | +#define BINNING_FILTER_H |
| 37 | +/** |
| 38 | +\author Anthony Goeckner |
| 39 | +@b LaserScanBinningFilter splits input scans into bins, ensuring that every output scan has the exact same number of readings as the number of bins. |
| 40 | +
|
| 41 | +**/ |
| 42 | + |
| 43 | +#include "filters/filter_base.hpp" |
| 44 | + |
| 45 | +#include <sensor_msgs/msg/laser_scan.hpp> |
| 46 | + |
| 47 | +namespace laser_filters |
| 48 | +{ |
| 49 | + |
| 50 | +class LaserScanBinningFilter : public filters::FilterBase<sensor_msgs::msg::LaserScan> |
| 51 | +{ |
| 52 | +public: |
| 53 | + |
| 54 | + uint num_bins_; |
| 55 | + |
| 56 | + bool configure() |
| 57 | + { |
| 58 | + num_bins_ = 360; |
| 59 | + getParam("num_bins", num_bins_); |
| 60 | + |
| 61 | + return true; |
| 62 | + } |
| 63 | + |
| 64 | + virtual ~LaserScanBinningFilter() |
| 65 | + { |
| 66 | + } |
| 67 | + |
| 68 | + bool update(const sensor_msgs::msg::LaserScan& input_scan, sensor_msgs::msg::LaserScan& filtered_scan) |
| 69 | + { |
| 70 | + // Copy data first. |
| 71 | + filtered_scan = input_scan; |
| 72 | + |
| 73 | + // Set up filtered_scan. |
| 74 | + filtered_scan.ranges.assign(num_bins_, std::numeric_limits<float>::quiet_NaN()); |
| 75 | + filtered_scan.intensities.assign(num_bins_, std::numeric_limits<float>::quiet_NaN()); |
| 76 | + filtered_scan.angle_increment = 2.0 * M_PI / static_cast<float>(num_bins_); |
| 77 | + |
| 78 | + // Convert to positive angles. |
| 79 | + float input_angle_min = fmodf(2.0 * M_PI + input_scan.angle_min, 2.0 * M_PI); |
| 80 | + |
| 81 | + // Need to account for case where scan wraps around, causing the data at angle 0 to actually occur |
| 82 | + // at the end of the scan. Therefore, we need to adjust the starting point of the scan. |
| 83 | + double angle_overlap = fmodf(input_scan.angle_increment * input_scan.ranges.size(), 2.0 * M_PI); |
| 84 | + |
| 85 | + // Update the scan time and angle_min to the oldest reading which will not be overlapped by a newer one. |
| 86 | + filtered_scan.scan_time = input_scan.scan_time + input_scan.time_increment * angle_overlap / input_scan.angle_increment; |
| 87 | + filtered_scan.time_increment = input_scan.time_increment * input_scan.ranges.size() / num_bins_; |
| 88 | + filtered_scan.angle_min = fmodf(input_angle_min + angle_overlap, 2.0 * M_PI); |
| 89 | + filtered_scan.angle_max = filtered_scan.angle_min + 2.0 * M_PI; |
| 90 | + |
| 91 | + // Assign data to bins. |
| 92 | + unsigned int i = 0; |
| 93 | + while(i < input_scan.ranges.size()) |
| 94 | + { |
| 95 | + // Calculate angle. |
| 96 | + double input_angle_relative = input_scan.angle_increment * i; |
| 97 | + double angle = fmodf(input_angle_relative - angle_overlap + 2.0 * M_PI, 2.0 * M_PI); |
| 98 | + |
| 99 | + // Calculate the bin index. |
| 100 | + unsigned int bin_index = static_cast<unsigned int>(floor(angle / filtered_scan.angle_increment)); |
| 101 | + |
| 102 | + // Copy the range and intensity values. |
| 103 | + filtered_scan.ranges[bin_index] = input_scan.ranges[i]; |
| 104 | + filtered_scan.intensities[bin_index] = input_scan.intensities[i]; |
| 105 | + |
| 106 | + i++; |
| 107 | + } |
| 108 | + return true; |
| 109 | + } |
| 110 | +}; |
| 111 | + |
| 112 | +} |
| 113 | + |
| 114 | +#endif // LASER_SCAN_INTENSITY_FILTER_H |
0 commit comments