Go to the documentation of this file.
43 #ifndef POLYGON_FILTER_H
44 #define POLYGON_FILTER_H
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>
69 virtual bool update(
const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan) {
return false; }
80 std::shared_ptr<dynamic_reconfigure::Server<laser_filters::PolygonFilterConfig>>
dyn_server_;
82 virtual void reconfigureCB(laser_filters::PolygonFilterConfig& config, uint32_t level);
92 bool update(
const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan)
override;
110 bool update(
const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan)
override;
113 void reconfigureCB(laser_filters::PolygonFilterConfig& config, uint32_t level)
override;
float co_sine_map_angle_min_
void checkCoSineMap(const sensor_msgs::LaserScan &input_scan)
boost::recursive_mutex own_mutex_
std::shared_ptr< dynamic_reconfigure::Server< laser_filters::PolygonFilterConfig > > dyn_server_
bool is_polygon_transformed_
laser_geometry::LaserProjection projector_
float co_sine_map_angle_max_
void reconfigureCB(laser_filters::PolygonFilterConfig &config, uint32_t level) override
virtual void configure(PolygonFilterConfig &config)
ros::Publisher polygon_pub_
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan) override
This is a filter that removes points in a laser scan inside of a polygon.
virtual bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan)
geometry_msgs::Polygon polygon_
double transform_timeout_
virtual void reconfigureCB(laser_filters::PolygonFilterConfig &config, uint32_t level)
tf::TransformListener tf_
bool configure() override
This is a filter that removes points in a laser scan inside of a polygon. It assumes that the transfo...
bool is_polygon_published_
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan) override
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
bool inPolygon(tf::Point &point) const
Eigen::ArrayXXd co_sine_map_
std::string polygon_frame_
laser_filters
Author(s): Tully Foote
autogenerated on Mon Apr 3 2023 02:51:57