scan_shadows_filter.h
Go to the documentation of this file.
1 /**********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008 Radu Bogdan Rusu <rusu@cs.tum.edu> and other laser_filters authors
5  *
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 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 copyright
14  * notice, this list of conditions and the following disclaimer in the
15  * documentation and/or other materials provided with the distribution.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *********************************************************************/
29 
30 /*
31  \author Radu Bogdan Rusu <rusu@cs.tum.edu> Tully Foote <tfoote@willowgarage.com>
32 */
33 
34 #ifndef LASER_SCAN_SHADOWS_FILTER_H
35 #define LASER_SCAN_SHADOWS_FILTER_H
36 
38 
39 #include <filters/filter_base.hpp>
40 #include <sensor_msgs/LaserScan.h>
41 #include <laser_filters/ScanShadowsFilterConfig.h>
42 #include <dynamic_reconfigure/server.h>
43 
44 namespace laser_filters
45 {
49 class ScanShadowsFilter : public filters::FilterBase<sensor_msgs::LaserScan>
50 {
51 public:
52  double laser_max_range_; // Used in laser scan projection
53  double min_angle_, max_angle_; // Filter angle threshold
54  int window_, neighbors_;
55  bool remove_shadow_start_point_; // Whether to also remove the start point of the shadow
56 
57  ScanShadowDetector shadow_detector_;
58 
59  std::shared_ptr<dynamic_reconfigure::Server<laser_filters::ScanShadowsFilterConfig>> dyn_server_;
60  boost::recursive_mutex own_mutex_;
61  ScanShadowsFilterConfig param_config;
62 
64  virtual ~ScanShadowsFilter();
65 
67  bool configure();
68 
69  void reconfigureCB(ScanShadowsFilterConfig& config, uint32_t level);
70 
78  bool update(const sensor_msgs::LaserScan& scan_in, sensor_msgs::LaserScan& scan_out);
79 private:
80  float angle_increment_;
81  std::vector<float> sin_map_;
82  std::vector<float> cos_map_;
83 
84  void prepareForInput(const float angle_increment);
85 };
86 }
87 
88 #endif // LASER_SCAN_SHADOWS_FILTER_H
filters::FilterBase
laser_filters::ScanShadowsFilter::dyn_server_
std::shared_ptr< dynamic_reconfigure::Server< laser_filters::ScanShadowsFilterConfig > > dyn_server_
Definition: scan_shadows_filter.h:113
laser_filters::ScanShadowsFilter::prepareForInput
void prepareForInput(const float angle_increment)
Definition: scan_shadows_filter.cpp:201
laser_filters::ScanShadowsFilter::min_angle_
double min_angle_
Definition: scan_shadows_filter.h:107
laser_filters::ScanShadowsFilter::~ScanShadowsFilter
virtual ~ScanShadowsFilter()
Definition: scan_shadows_filter.cpp:69
laser_filters::ScanShadowsFilter::angle_increment_
float angle_increment_
Definition: scan_shadows_filter.h:134
laser_filters::ScanShadowsFilter::remove_shadow_start_point_
bool remove_shadow_start_point_
Definition: scan_shadows_filter.h:109
laser_filters::ScanShadowsFilter::shadow_detector_
ScanShadowDetector shadow_detector_
Definition: scan_shadows_filter.h:111
laser_filters::ScanShadowsFilter::param_config
ScanShadowsFilterConfig param_config
Definition: scan_shadows_filter.h:115
filter_base.hpp
laser_filters::ScanShadowsFilter::update
bool update(const sensor_msgs::LaserScan &scan_in, sensor_msgs::LaserScan &scan_out)
Filter shadow points based on 3 global parameters: min_angle, max_angle and window....
Definition: scan_shadows_filter.cpp:156
laser_filters::ScanShadowsFilter::ScanShadowsFilter
ScanShadowsFilter()
Definition: scan_shadows_filter.cpp:65
laser_filters::ScanShadowsFilter::configure
bool configure()
Definition: scan_shadows_filter.cpp:73
laser_filters::ScanShadowsFilter::reconfigureCB
void reconfigureCB(ScanShadowsFilterConfig &config, uint32_t level)
Definition: scan_shadows_filter.cpp:141
laser_filters::ScanShadowsFilter::max_angle_
double max_angle_
Definition: scan_shadows_filter.h:107
scan_shadow_detector.h
laser_filters::ScanShadowsFilter::sin_map_
std::vector< float > sin_map_
Definition: scan_shadows_filter.h:135
laser_filters::ScanShadowsFilter::laser_max_range_
double laser_max_range_
Definition: scan_shadows_filter.h:106
laser_filters::ScanShadowsFilter::neighbors_
int neighbors_
Definition: scan_shadows_filter.h:108
laser_filters::ScanShadowsFilter::own_mutex_
boost::recursive_mutex own_mutex_
Definition: scan_shadows_filter.h:114
laser_filters::ScanShadowsFilter::window_
int window_
Definition: scan_shadows_filter.h:108
laser_filters
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
Definition: angular_bounds_filter.h:43
laser_filters::ScanShadowsFilter::cos_map_
std::vector< float > cos_map_
Definition: scan_shadows_filter.h:136


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