laser_filters::LaserArrayFilter Class Reference

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

#include <array_filter.h>

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 47 of file array_filter.h.


Constructor & Destructor Documentation

laser_filters::LaserArrayFilter::LaserArrayFilter (  ) 

Constructor.

Parameters:
averaging_length How many scans to average over.

Definition at line 33 of file array_filter.cpp.

laser_filters::LaserArrayFilter::~LaserArrayFilter (  ) 

Definition at line 74 of file array_filter.cpp.


Member Function Documentation

bool laser_filters::LaserArrayFilter::configure (  ) 

Definition at line 39 of file array_filter.cpp.

bool laser_filters::LaserArrayFilter::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 83 of file array_filter.cpp.


Member Data Documentation

Definition at line 68 of file array_filter.h.

Definition at line 62 of file array_filter.h.

Definition at line 66 of file array_filter.h.

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

Definition at line 72 of file array_filter.h.

How many scans to average over.

Definition at line 63 of file array_filter.h.

XmlRpc::XmlRpcValue laser_filters::LaserArrayFilter::range_config_ [private]

How many data point are in each row.

Definition at line 65 of file array_filter.h.

filters::MultiChannelFilterChain<float>* laser_filters::LaserArrayFilter::range_filter_ [private]
Todo:
cache only shallow info not full scan

Definition at line 71 of file array_filter.h.

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

Protection from multi threaded programs.

Definition at line 69 of file array_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