Public Member Functions | Private Attributes
laser_filters::LaserArrayFilter Class Reference

A class to provide median filtering of laser scans in time. More...

#include <array_filter.h>

Inheritance diagram for laser_filters::LaserArrayFilter:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool configure ()
 LaserArrayFilter ()
 Constructor.
bool update (const sensor_msgs::LaserScan &scan_in, sensor_msgs::LaserScan &scan_out)
 Update the filter and get the response.
 ~LaserArrayFilter ()

Private Attributes

boost::mutex data_lock
unsigned int filter_length_
XmlRpc::XmlRpcValue intensity_config_
filters::MultiChannelFilterChain
< float > * 
intensity_filter_
unsigned int num_ranges_
 How many scans to average over.
XmlRpc::XmlRpcValue range_config_
 How many data point are in each row.
filters::MultiChannelFilterChain
< float > * 
range_filter_
sensor_msgs::LaserScan temp_scan_
 Protection from multi threaded programs.

Detailed Description

A class to provide median filtering of laser scans in time.

Definition at line 49 of file array_filter.h.


Constructor & Destructor Documentation

Constructor.

Parameters:
averaging_lengthHow many scans to average over.

Definition at line 35 of file array_filter.cpp.

Definition at line 76 of file array_filter.cpp.


Member Function Documentation

Implements filters::FilterBase< sensor_msgs::LaserScan >.

Definition at line 41 of file array_filter.cpp.

bool laser_filters::LaserArrayFilter::update ( const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::LaserScan &  scan_out 
) [virtual]

Update the filter and get the response.

Parameters:
scan_inThe new scan to filter
scan_outThe filtered scan

Quickly pass through all data

Todo:
don't copy data too
Todo:
check for length of intensities too

Implements filters::FilterBase< sensor_msgs::LaserScan >.

Definition at line 85 of file array_filter.cpp.


Member Data Documentation

Definition at line 74 of file array_filter.h.

Definition at line 68 of file array_filter.h.

Definition at line 72 of file array_filter.h.

Definition at line 78 of file array_filter.h.

How many scans to average over.

Definition at line 69 of file array_filter.h.

How many data point are in each row.

Definition at line 71 of file array_filter.h.

Todo:
cache only shallow info not full scan

Definition at line 77 of file array_filter.h.

sensor_msgs::LaserScan laser_filters::LaserArrayFilter::temp_scan_ [private]

Protection from multi threaded programs.

Definition at line 75 of file array_filter.h.


The documentation for this class was generated from the following files:


laser_filters
Author(s): Tully Foote
autogenerated on Mon Oct 6 2014 01:45:08