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.hpp>
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 LaserScanPolygonFilterBase : public filters::FilterBase<sensor_msgs::LaserScan> {
65 public:
66  virtual bool configure();
67  virtual void configure(PolygonFilterConfig& config) { reconfigureCB(config, 0); }
68 
69  virtual bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan) { return false; }
70 
71 protected:
73  boost::recursive_mutex own_mutex_;
74  // configuration
75  std::string polygon_frame_;
76  geometry_msgs::Polygon polygon_;
79  bool is_polygon_published_ = false;
80  std::shared_ptr<dynamic_reconfigure::Server<laser_filters::PolygonFilterConfig>> dyn_server_;
81 
82  virtual void reconfigureCB(laser_filters::PolygonFilterConfig& config, uint32_t level);
83 
84  // checks if points in polygon
85  bool inPolygon(tf::Point& point) const;
86 
87  void publishPolygon();
88 };
89 
91 public:
92  bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan) override;
93 
94 private:
95  // configuration
97  // tf listener to transform scans into the polygon_frame
99 };
100 
108 public:
109  bool configure() override;
110  bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan) override;
111 
112 protected:
113  void reconfigureCB(laser_filters::PolygonFilterConfig& config, uint32_t level) override;
114 
115 private:
117 
118  Eigen::ArrayXXd co_sine_map_;
122 
123  void checkCoSineMap(const sensor_msgs::LaserScan& input_scan);
124 };
125 }
126 #endif /* polygon_filter.h */
laser_filters::LaserScanPolygonFilterBase::publishPolygon
void publishPolygon()
Definition: polygon_filter.cpp:313
laser_filters::LaserScanPolygonFilterBase::invert_filter_
bool invert_filter_
Definition: polygon_filter.h:78
filters::FilterBase
ros::Publisher
laser_filters::StaticLaserScanPolygonFilter::co_sine_map_angle_min_
float co_sine_map_angle_min_
Definition: polygon_filter.h:119
laser_filters::LaserScanPolygonFilter
Definition: polygon_filter.h:90
laser_geometry::LaserProjection
laser_filters::StaticLaserScanPolygonFilter::checkCoSineMap
void checkCoSineMap(const sensor_msgs::LaserScan &input_scan)
Definition: polygon_filter.cpp:430
laser_filters::LaserScanPolygonFilterBase::own_mutex_
boost::recursive_mutex own_mutex_
Definition: polygon_filter.h:73
laser_filters::LaserScanPolygonFilterBase::dyn_server_
std::shared_ptr< dynamic_reconfigure::Server< laser_filters::PolygonFilterConfig > > dyn_server_
Definition: polygon_filter.h:80
laser_filters::StaticLaserScanPolygonFilter::is_polygon_transformed_
bool is_polygon_transformed_
Definition: polygon_filter.h:121
laser_filters::LaserScanPolygonFilter::projector_
laser_geometry::LaserProjection projector_
Definition: polygon_filter.h:96
laser_filters::StaticLaserScanPolygonFilter::co_sine_map_angle_max_
float co_sine_map_angle_max_
Definition: polygon_filter.h:120
laser_filters::StaticLaserScanPolygonFilter::reconfigureCB
void reconfigureCB(laser_filters::PolygonFilterConfig &config, uint32_t level) override
Definition: polygon_filter.cpp:544
filter_base.hpp
laser_geometry.h
tf::Point
tf::Vector3 Point
laser_filters::LaserScanPolygonFilterBase::configure
virtual void configure(PolygonFilterConfig &config)
Definition: polygon_filter.h:67
laser_filters::LaserScanPolygonFilterBase::polygon_pub_
ros::Publisher polygon_pub_
Definition: polygon_filter.h:72
laser_filters::StaticLaserScanPolygonFilter::update
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan) override
Definition: polygon_filter.cpp:459
laser_filters::LaserScanPolygonFilterBase
This is a filter that removes points in a laser scan inside of a polygon.
Definition: polygon_filter.h:64
laser_filters::LaserScanPolygonFilterBase::update
virtual bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan)
Definition: polygon_filter.h:69
laser_filters::LaserScanPolygonFilterBase::polygon_
geometry_msgs::Polygon polygon_
Definition: polygon_filter.h:76
laser_filters::LaserScanPolygonFilterBase::configure
virtual bool configure()
Definition: polygon_filter.cpp:251
laser_filters::LaserScanPolygonFilterBase::polygon_padding_
double polygon_padding_
Definition: polygon_filter.h:77
laser_filters::StaticLaserScanPolygonFilter::transform_timeout_
double transform_timeout_
Definition: polygon_filter.h:116
laser_filters::LaserScanPolygonFilterBase::reconfigureCB
virtual void reconfigureCB(laser_filters::PolygonFilterConfig &config, uint32_t level)
Definition: polygon_filter.cpp:326
transform_listener.h
point_cloud_conversion.h
transform_datatypes.h
laser_filters::LaserScanPolygonFilter::tf_
tf::TransformListener tf_
Definition: polygon_filter.h:98
tf::TransformListener
laser_filters::StaticLaserScanPolygonFilter::configure
bool configure() override
Definition: polygon_filter.cpp:420
laser_filters::StaticLaserScanPolygonFilter
This is a filter that removes points in a laser scan inside of a polygon. It assumes that the transfo...
Definition: polygon_filter.h:107
laser_filters::LaserScanPolygonFilterBase::is_polygon_published_
bool is_polygon_published_
Definition: polygon_filter.h:79
laser_filters::LaserScanPolygonFilter::update
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan) override
Definition: polygon_filter.cpp:334
laser_filters
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
Definition: angular_bounds_filter.h:43
laser_filters::LaserScanPolygonFilterBase::inPolygon
bool inPolygon(tf::Point &point) const
Definition: polygon_filter.cpp:298
laser_filters::StaticLaserScanPolygonFilter::co_sine_map_
Eigen::ArrayXXd co_sine_map_
Definition: polygon_filter.h:118
laser_filters::LaserScanPolygonFilterBase::polygon_frame_
std::string polygon_frame_
Definition: polygon_filter.h:75


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