Go to the documentation of this file.
30 #ifndef LASER_SCAN_ARRAY_FILTER_H
31 #define LASER_SCAN_ARRAY_FILTER_H
37 #include "boost/thread/mutex.hpp"
38 #include "boost/scoped_ptr.hpp"
39 #include "sensor_msgs/LaserScan.h"
44 #include "boost/thread/mutex.hpp"
64 bool update(
const sensor_msgs::LaserScan& scan_in, sensor_msgs::LaserScan& scan_out);
89 #endif //LASER_SCAN_UTILS_LASERSCAN_H
filters::MultiChannelFilterChain< float > * range_filter_
sensor_msgs::LaserScan temp_scan_
Protection from multi threaded programs.
XmlRpc::XmlRpcValue range_config_
How many data point are in each row.
LaserArrayFilter()
Constructor.
unsigned int filter_length_
bool update(const sensor_msgs::LaserScan &scan_in, sensor_msgs::LaserScan &scan_out)
Update the filter and get the response.
filters::MultiChannelFilterChain< float > * intensity_filter_
unsigned int num_ranges_
How many scans to average over.
A class to provide median filtering of laser scans in time.
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
XmlRpc::XmlRpcValue intensity_config_
laser_filters
Author(s): Tully Foote
autogenerated on Wed Mar 27 2024 02:53:20