32 #ifndef LASER_SCAN_SECTOR_FILTER_IN_PLACE_H
33 #define LASER_SCAN_SECTOR_FILTER_IN_PLACE_H
35 #include <dynamic_reconfigure/server.h>
36 #include <laser_filters/SectorFilterConfig.h>
39 #include <sensor_msgs/LaserScan.h>
50 bool update(
const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& output_scan);
55 std::shared_ptr<dynamic_reconfigure::Server<SectorFilterConfig>>
dyn_server_;
56 void reconfigureCB(SectorFilterConfig& config, uint32_t level);
59 SectorFilterConfig
config_ = SectorFilterConfig::__getDefault__();
64 #endif // LASER_SCAN_SECTOR_FILTER_IN_PLACE_H