polygon_filter.h
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  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
27  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
28  * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
29  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
30  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
31  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
32  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
33  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
34  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
35  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
36  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
37  *
38  *
39  *
40  * polygon_filter.h
41  */
42 
43 #ifndef POLYGON_FILTER_H
44 #define POLYGON_FILTER_H
45 
46 #include <filters/filter_base.h>
47 
48 #include <sensor_msgs/LaserScan.h>
51 #include <geometry_msgs/Polygon.h>
52 #include <geometry_msgs/PolygonStamped.h>
53 #include <laser_filters/PolygonFilterConfig.h>
54 #include <dynamic_reconfigure/server.h>
55 
56 #include <tf/transform_datatypes.h>
57 #include <tf/transform_listener.h>
58 
59 namespace laser_filters
60 {
64 class LaserScanPolygonFilter : public filters::FilterBase<sensor_msgs::LaserScan>
65 {
66 public:
68  bool configure();
69 
70  bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan);
71 
72 private:
73  // configuration
75  std::shared_ptr<dynamic_reconfigure::Server<laser_filters::PolygonFilterConfig>> dyn_server_;
76  void reconfigureCB(laser_filters::PolygonFilterConfig& config, uint32_t level);
77  boost::recursive_mutex own_mutex_;
78  std::string polygon_frame_;
79  geometry_msgs::Polygon polygon_;
82 
83  // checks if points in polygon
84  bool inPolygon(tf::Point& point) const;
85 
87 
88  // tf listener to transform scans into the polygon_frame
90 };
91 }
92 #endif /* polygon_filter.h */
laser_geometry::LaserProjection projector_
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
std::shared_ptr< dynamic_reconfigure::Server< laser_filters::PolygonFilterConfig > > dyn_server_
tf::Vector3 Point
bool inPolygon(tf::Point &point) const
This is a filter that removes points in a laser scan inside of a polygon.
void reconfigureCB(laser_filters::PolygonFilterConfig &config, uint32_t level)
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan)


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