Public Member Functions | Public Attributes | List of all members
laser_filters::ScanShadowsFilter Class Reference

#include <scan_shadows_filter.h>

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

Public Member Functions

bool configure ()
 
 ScanShadowsFilter ()
 
bool update (const sensor_msgs::LaserScan &scan_in, sensor_msgs::LaserScan &scan_out)
 Filter shadow points based on 3 global parameters: min_angle, max_angle and window. {min,max}_angle specify the allowed angle interval (in degrees) between the created lines (see getAngleWithViewPoint). Window specifies how many consecutive measurements to take into account for one point. More...
 
virtual ~ScanShadowsFilter ()
 
- 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 ()
 
std::string getType ()
 
virtual ~FilterBase ()
 

Public Attributes

double laser_max_range_
 
double max_angle_
 
double min_angle_
 
int neighbors_
 
bool remove_shadow_start_point_
 
ScanShadowDetector shadow_detector_
 
int window_
 

Additional Inherited Members

- Protected Member Functions inherited from filters::FilterBase< sensor_msgs::LaserScan >
bool getParam (const std::string &name, std::string &value)
 
bool getParam (const std::string &name, XmlRpc::XmlRpcValue &value)
 
bool getParam (const std::string &name, double &value)
 
bool getParam (const std::string &name, std::vector< double > &value)
 
bool getParam (const std::string &name, unsigned int &value)
 
bool getParam (const std::string &name, int &value)
 
bool getParam (const std::string &name, std::vector< std::string > &value)
 
bool getParam (const std::string &name, bool &value)
 
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

ScanShadowsFilter is a simple filter that filters shadow points in a laser scan line

Definition at line 52 of file scan_shadows_filter.h.

Constructor & Destructor Documentation

laser_filters::ScanShadowsFilter::ScanShadowsFilter ( )
inline

Definition at line 63 of file scan_shadows_filter.h.

virtual laser_filters::ScanShadowsFilter::~ScanShadowsFilter ( )
inlinevirtual

Definition at line 122 of file scan_shadows_filter.h.

Member Function Documentation

bool laser_filters::ScanShadowsFilter::configure ( )
inlinevirtual

Configure the filter from XML

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

Definition at line 68 of file scan_shadows_filter.h.

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

Filter shadow points based on 3 global parameters: min_angle, max_angle and window. {min,max}_angle specify the allowed angle interval (in degrees) between the created lines (see getAngleWithViewPoint). Window specifies how many consecutive measurements to take into account for one point.

Parameters
scan_inthe input LaserScan message
scan_outthe output LaserScan message

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

Definition at line 134 of file scan_shadows_filter.h.

Member Data Documentation

double laser_filters::ScanShadowsFilter::laser_max_range_

Definition at line 55 of file scan_shadows_filter.h.

double laser_filters::ScanShadowsFilter::max_angle_

Definition at line 56 of file scan_shadows_filter.h.

double laser_filters::ScanShadowsFilter::min_angle_

Definition at line 56 of file scan_shadows_filter.h.

int laser_filters::ScanShadowsFilter::neighbors_

Definition at line 57 of file scan_shadows_filter.h.

bool laser_filters::ScanShadowsFilter::remove_shadow_start_point_

Definition at line 58 of file scan_shadows_filter.h.

ScanShadowDetector laser_filters::ScanShadowsFilter::shadow_detector_

Definition at line 60 of file scan_shadows_filter.h.

int laser_filters::ScanShadowsFilter::window_

Definition at line 57 of file scan_shadows_filter.h.


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


laser_filters
Author(s): Tully Foote
autogenerated on Tue Mar 17 2020 03:40:02