speckle_filter.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Robot Operating System code by Eurotec B.V.
5  * Copyright (c) 2020, Eurotec B.V.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * 1. Redistributions of source code must retain the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer.
15  *
16  * 2. Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  *
21  * 3. Neither the name of the copyright holder nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
27  * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
28  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
29  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
30  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
31  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
32  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
33  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
34  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
35  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
36  *
37  * speckle_filter.cpp
38  */
39 
41 #include <ros/node_handle.h>
42 
43 namespace laser_filters
44 {
46 {
47  validator_ = 0;
48 }
49 
51 {
52  if (!validator_)
53  {
54  delete validator_;
55  }
56 }
57 
59 {
60  ros::NodeHandle private_nh("~" + getName());
61  dyn_server_.reset(new dynamic_reconfigure::Server<laser_filters::SpeckleFilterConfig>(own_mutex_, private_nh));
62  dynamic_reconfigure::Server<laser_filters::SpeckleFilterConfig>::CallbackType f;
63  f = [this](auto& config, auto level){ reconfigureCB(config, level); };
64  dyn_server_->setCallback(f);
65 
66  getParam("filter_type", config_.filter_type);
67  getParam("max_range", config_.max_range);
68  getParam("max_range_difference", config_.max_range_difference);
69  getParam("filter_window", config_.filter_window);
70  dyn_server_->updateConfig(config_);
71  return true;
72 }
73 
74 bool LaserScanSpeckleFilter::update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& output_scan)
75 {
76  boost::recursive_mutex::scoped_lock lock(own_mutex_);
77 
78  output_scan = input_scan;
79 
80  std::vector<bool> &valid_ranges = valid_ranges_work_;
81 
82  /*Check if range size is big enough to use the filter window */
83  if (output_scan.ranges.size() <= config_.filter_window + 1)
84  {
85  ROS_ERROR("Scan ranges size is too small: size = %ld", output_scan.ranges.size());
86  return false;
87  }
88 
89  size_t i = 0;
90  size_t i_max = input_scan.ranges.size();
91  valid_ranges.clear();
92  while (i < i_max) {
93  bool out_of_range = output_scan.ranges[i] > config_.max_range;
94  valid_ranges.push_back(out_of_range);
95  ++i;
96  }
97 
98  i = 0;
99  i_max = input_scan.ranges.size() - config_.filter_window + 1;
100  while (i < i_max) {
101  bool window_valid = validator_->checkWindowValid(
102  output_scan, i, config_.filter_window, config_.max_range_difference
103  );
104  if (window_valid) {
105  size_t j = i, j_max = i + config_.filter_window;
106  do {
107  valid_ranges[j++] = true;
108  } while (j < j_max);
109  }
110  ++i;
111  }
112 
113  i = 0;
114  i_max = valid_ranges.size();
115  while (i < i_max) {
116  if (!valid_ranges[i]) {
117  output_scan.ranges[i] = std::numeric_limits<float>::quiet_NaN();
118  }
119  ++i;
120  }
121 
122  return true;
123 }
124 
125 void LaserScanSpeckleFilter::reconfigureCB(laser_filters::SpeckleFilterConfig& config, uint32_t level)
126 {
127  config_ = config;
128 
129  switch (config_.filter_type) {
130  case laser_filters::SpeckleFilter_RadiusOutlier:
131  if (validator_)
132  {
133  delete validator_;
134  }
136  break;
137 
138  case laser_filters::SpeckleFilter_Distance:
139  if (validator_)
140  {
141  delete validator_;
142  }
144  break;
145 
146  default:
147  break;
148  }
149 
150 }
151 }
node_handle.h
laser_filters::LaserScanSpeckleFilter::config_
SpeckleFilterConfig config_
Definition: speckle_filter.h:170
laser_filters::WindowValidator::checkWindowValid
virtual bool checkWindowValid(const sensor_msgs::LaserScan &scan, size_t idx, size_t window, double max_range_difference)=0
laser_filters::LaserScanSpeckleFilter::~LaserScanSpeckleFilter
~LaserScanSpeckleFilter()
Definition: speckle_filter.cpp:50
laser_filters::RadiusOutlierWindowValidator
Definition: speckle_filter.h:81
laser_filters::LaserScanSpeckleFilter::LaserScanSpeckleFilter
LaserScanSpeckleFilter()
Definition: speckle_filter.cpp:45
f
f
filters::FilterBase< sensor_msgs::LaserScan >::getParam
bool getParam(const std::string &name, bool &value) const
laser_filters::DistanceWindowValidator
Definition: speckle_filter.h:58
laser_filters::LaserScanSpeckleFilter::validator_
WindowValidator * validator_
Definition: speckle_filter.h:171
laser_filters::LaserScanSpeckleFilter::reconfigureCB
void reconfigureCB(laser_filters::SpeckleFilterConfig &config, uint32_t level)
Definition: speckle_filter.cpp:125
laser_filters::LaserScanSpeckleFilter::update
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &output_scan)
Definition: speckle_filter.cpp:74
laser_filters::LaserScanSpeckleFilter::dyn_server_
std::shared_ptr< dynamic_reconfigure::Server< laser_filters::SpeckleFilterConfig > > dyn_server_
Definition: speckle_filter.h:166
laser_filters::LaserScanSpeckleFilter::valid_ranges_work_
std::vector< bool > valid_ranges_work_
Definition: speckle_filter.h:174
laser_filters::LaserScanSpeckleFilter::configure
bool configure()
Definition: speckle_filter.cpp:58
filters::FilterBase< sensor_msgs::LaserScan >::getName
const std::string & getName() const
ROS_ERROR
#define ROS_ERROR(...)
laser_filters
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
Definition: angular_bounds_filter.h:43
speckle_filter.h
ros::NodeHandle
laser_filters::LaserScanSpeckleFilter::own_mutex_
boost::recursive_mutex own_mutex_
Definition: speckle_filter.h:168


laser_filters
Author(s): Tully Foote
autogenerated on Mon Apr 3 2023 02:51:57