Public Member Functions | Private Attributes | List of all members
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]

Public Member Functions

bool configure ()
 
 LaserArrayFilter ()
 Constructor. More...
 
bool update (const sensor_msgs::LaserScan &scan_in, sensor_msgs::LaserScan &scan_out)
 Update the filter and get the response. More...
 
 ~LaserArrayFilter ()
 
- Public Member Functions inherited from filters::FilterBase< sensor_msgs::LaserScan >
bool configure (const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
 
bool configure (XmlRpc::XmlRpcValue &config)
 
 FilterBase ()
 
const std::string & getName () const
 
std::string getType ()
 
virtual ~FilterBase ()
 

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. More...
 
XmlRpc::XmlRpcValue range_config_
 How many data point are in each row. More...
 
filters::MultiChannelFilterChain< float > * range_filter_
 
sensor_msgs::LaserScan temp_scan_
 Protection from multi threaded programs. More...
 

Additional Inherited Members

- Protected Member Functions inherited from filters::FilterBase< sensor_msgs::LaserScan >
bool getParam (const std::string &name, std::string &value) const
 
bool getParam (const std::string &name, XmlRpc::XmlRpcValue &value) const
 
bool getParam (const std::string &name, double &value) const
 
bool getParam (const std::string &name, std::vector< double > &value) const
 
bool getParam (const std::string &name, unsigned int &value) const
 
bool getParam (const std::string &name, int &value) const
 
bool getParam (const std::string &name, std::vector< std::string > &value) const
 
bool getParam (const std::string &name, bool &value) const
 
bool loadConfiguration (XmlRpc::XmlRpcValue &config)
 
- Protected Attributes inherited from filters::FilterBase< sensor_msgs::LaserScan >
bool configured_
 
std::string filter_name_
 
std::string filter_type_
 
string_map_t params_
 

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

◆ LaserArrayFilter()

laser_filters::LaserArrayFilter::LaserArrayFilter ( )

Constructor.

Parameters
averaging_lengthHow many scans to average over.

Definition at line 35 of file array_filter.cpp.

◆ ~LaserArrayFilter()

laser_filters::LaserArrayFilter::~LaserArrayFilter ( )

Definition at line 76 of file array_filter.cpp.

Member Function Documentation

◆ configure()

bool laser_filters::LaserArrayFilter::configure ( )
virtual

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

Definition at line 41 of file array_filter.cpp.

◆ update()

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

◆ data_lock

boost::mutex laser_filters::LaserArrayFilter::data_lock
private

Definition at line 74 of file array_filter.h.

◆ filter_length_

unsigned int laser_filters::LaserArrayFilter::filter_length_
private

Definition at line 68 of file array_filter.h.

◆ intensity_config_

XmlRpc::XmlRpcValue laser_filters::LaserArrayFilter::intensity_config_
private

Definition at line 72 of file array_filter.h.

◆ intensity_filter_

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

Definition at line 78 of file array_filter.h.

◆ num_ranges_

unsigned int laser_filters::LaserArrayFilter::num_ranges_
private

How many scans to average over.

Definition at line 69 of file array_filter.h.

◆ range_config_

XmlRpc::XmlRpcValue laser_filters::LaserArrayFilter::range_config_
private

How many data point are in each row.

Definition at line 71 of file array_filter.h.

◆ range_filter_

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

Definition at line 77 of file array_filter.h.

◆ temp_scan_

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 Feb 28 2022 22:39:24