sector_filter.h
Go to the documentation of this file.
1 /*********************************************************************
2 * BSD 2-Clause License
3 *
4 * Copyright (c) 2021, Jimmy F. Klarke
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 are met:
9 *
10 * 1. Redistributions of source code must retain the above copyright notice,
11 * this list of conditions and the following disclaimer.
12 *
13 * 2. Redistributions in binary form must reproduce the above copyright notice,
14 * this list of conditions and the following disclaimer in the documentation
15 * 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 HOLDER 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 * \author: Jimmy F. Klarke
30 *********************************************************************/
31 
32 #ifndef LASER_SCAN_SECTOR_FILTER_IN_PLACE_H
33 #define LASER_SCAN_SECTOR_FILTER_IN_PLACE_H
34 
35 #include <dynamic_reconfigure/server.h>
36 #include <laser_filters/SectorFilterConfig.h>
37 
38 #include <filters/filter_base.h>
39 #include <sensor_msgs/LaserScan.h>
40 
41 namespace laser_filters
42 {
43 
44 class LaserScanSectorFilter : public filters::FilterBase<sensor_msgs::LaserScan>
45 {
46 public:
48  bool configure();
49  bool isClearInside();
50  bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& output_scan);
51 
53 
54 private:
55  std::shared_ptr<dynamic_reconfigure::Server<SectorFilterConfig>> dyn_server_;
56  void reconfigureCB(SectorFilterConfig& config, uint32_t level);
57  boost::recursive_mutex own_mutex_;
58 
59  SectorFilterConfig config_ = SectorFilterConfig::__getDefault__();
60 };
61 
62 } // end namespace laser_filters
63 
64 #endif // LASER_SCAN_SECTOR_FILTER_IN_PLACE_H
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
boost::recursive_mutex own_mutex_
Definition: sector_filter.h:57
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &output_scan)
std::shared_ptr< dynamic_reconfigure::Server< SectorFilterConfig > > dyn_server_
Definition: sector_filter.h:55
void reconfigureCB(SectorFilterConfig &config, uint32_t level)


laser_filters
Author(s): Tully Foote
autogenerated on Mon Feb 28 2022 22:39:24