laser_filters::LaserMedianFilter Class Reference

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

#include <median_filter.h>

List of all members.

Public Member Functions

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

Private Attributes

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

Detailed Description

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

Definition at line 49 of file median_filter.h.


Constructor & Destructor Documentation

laser_filters::LaserMedianFilter::LaserMedianFilter (  ) 

Constructor.

Parameters:
averaging_length How many scans to average over.

Definition at line 35 of file median_filter.cpp.

laser_filters::LaserMedianFilter::~LaserMedianFilter (  ) 

Definition at line 60 of file median_filter.cpp.


Member Function Documentation

bool laser_filters::LaserMedianFilter::configure (  ) 

Definition at line 41 of file median_filter.cpp.

bool laser_filters::LaserMedianFilter::update ( const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::LaserScan &  scan_out 
)

Update the filter and get the response.

Parameters:
scan_in The new scan to filter
scan_out The filtered scan

Quickly pass through all data

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

Definition at line 66 of file median_filter.cpp.


Member Data Documentation

How many data point are in each row.

Definition at line 71 of file median_filter.h.

Definition at line 68 of file median_filter.h.

filters::MultiChannelFilterChain<float>* laser_filters::LaserMedianFilter::intensity_filter_ [private]

Definition at line 77 of file median_filter.h.

How many scans to average over.

Definition at line 69 of file median_filter.h.

filters::MultiChannelFilterChain<float>* laser_filters::LaserMedianFilter::range_filter_ [private]

Definition at line 76 of file median_filter.h.

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

Protection from multi threaded programs.

Definition at line 72 of file median_filter.h.

XmlRpc::XmlRpcValue laser_filters::LaserMedianFilter::xmlrpc_value_ [private]
Todo:
cache only shallow info not full scan

Definition at line 74 of file median_filter.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables


laser_filters
Author(s): Tully Foote
autogenerated on Fri Jan 11 09:16:04 2013