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> 70 bool update(
const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan);
75 std::shared_ptr<dynamic_reconfigure::Server<laser_filters::PolygonFilterConfig>>
dyn_server_;
76 void reconfigureCB(laser_filters::PolygonFilterConfig& config, uint32_t level);
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_
ros::Publisher polygon_pub_
bool inPolygon(tf::Point &point) const
tf::TransformListener tf_
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)
boost::recursive_mutex own_mutex_
std::string polygon_frame_
geometry_msgs::Polygon polygon_