Go to the documentation of this file.
34 #ifndef LASER_SCAN_SHADOWS_FILTER_H
35 #define LASER_SCAN_SHADOWS_FILTER_H
40 #include <sensor_msgs/LaserScan.h>
41 #include <laser_filters/ScanShadowsFilterConfig.h>
42 #include <dynamic_reconfigure/server.h>
59 std::shared_ptr<dynamic_reconfigure::Server<laser_filters::ScanShadowsFilterConfig>>
dyn_server_;
69 void reconfigureCB(ScanShadowsFilterConfig& config, uint32_t level);
78 bool update(
const sensor_msgs::LaserScan& scan_in, sensor_msgs::LaserScan& scan_out);
88 #endif // LASER_SCAN_SHADOWS_FILTER_H
std::shared_ptr< dynamic_reconfigure::Server< laser_filters::ScanShadowsFilterConfig > > dyn_server_
void prepareForInput(const float angle_increment)
virtual ~ScanShadowsFilter()
bool remove_shadow_start_point_
ScanShadowDetector shadow_detector_
ScanShadowsFilterConfig param_config
bool update(const sensor_msgs::LaserScan &scan_in, sensor_msgs::LaserScan &scan_out)
Filter shadow points based on 3 global parameters: min_angle, max_angle and window....
void reconfigureCB(ScanShadowsFilterConfig &config, uint32_t level)
std::vector< float > sin_map_
boost::recursive_mutex own_mutex_
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
std::vector< float > cos_map_
laser_filters
Author(s): Tully Foote
autogenerated on Mon Apr 3 2023 02:51:57