Public Member Functions | Public Attributes | Private Member Functions | Private 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 ()
 
void reconfigureCB (ScanShadowsFilterConfig &config, uint32_t level)
 
 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 () const
 
std::string getType ()
 
virtual bool update (const T &data_in, T &data_out)=0
 
virtual ~FilterBase ()
 

Public Attributes

std::shared_ptr< dynamic_reconfigure::Server< laser_filters::ScanShadowsFilterConfig > > dyn_server_
 
double laser_max_range_
 
double max_angle_
 
double min_angle_
 
int neighbors_
 
boost::recursive_mutex own_mutex_
 
ScanShadowsFilterConfig param_config
 
bool remove_shadow_start_point_
 
ScanShadowDetector shadow_detector_
 
int window_
 

Private Member Functions

void prepareForInput (const float angle_increment)
 

Private Attributes

float angle_increment_
 
std::vector< float > cos_map_
 
std::vector< float > sin_map_
 

Additional Inherited Members

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

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

Definition at line 76 of file scan_shadows_filter.h.

Constructor & Destructor Documentation

◆ ScanShadowsFilter()

laser_filters::ScanShadowsFilter::ScanShadowsFilter ( )

Definition at line 65 of file scan_shadows_filter.cpp.

◆ ~ScanShadowsFilter()

laser_filters::ScanShadowsFilter::~ScanShadowsFilter ( )
virtual

Definition at line 69 of file scan_shadows_filter.cpp.

Member Function Documentation

◆ configure()

bool laser_filters::ScanShadowsFilter::configure ( )
virtual

Configure the filter from XML

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

Definition at line 73 of file scan_shadows_filter.cpp.

◆ prepareForInput()

void laser_filters::ScanShadowsFilter::prepareForInput ( const float  angle_increment)
private

Definition at line 201 of file scan_shadows_filter.cpp.

◆ reconfigureCB()

void laser_filters::ScanShadowsFilter::reconfigureCB ( ScanShadowsFilterConfig &  config,
uint32_t  level 
)

Definition at line 141 of file scan_shadows_filter.cpp.

◆ update()

bool laser_filters::ScanShadowsFilter::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.

Parameters
scan_inthe input LaserScan message
scan_outthe output LaserScan message

Definition at line 156 of file scan_shadows_filter.cpp.

Member Data Documentation

◆ angle_increment_

float laser_filters::ScanShadowsFilter::angle_increment_
private

Definition at line 134 of file scan_shadows_filter.h.

◆ cos_map_

std::vector<float> laser_filters::ScanShadowsFilter::cos_map_
private

Definition at line 136 of file scan_shadows_filter.h.

◆ dyn_server_

std::shared_ptr<dynamic_reconfigure::Server<laser_filters::ScanShadowsFilterConfig> > laser_filters::ScanShadowsFilter::dyn_server_

Definition at line 113 of file scan_shadows_filter.h.

◆ laser_max_range_

double laser_filters::ScanShadowsFilter::laser_max_range_

Definition at line 106 of file scan_shadows_filter.h.

◆ max_angle_

double laser_filters::ScanShadowsFilter::max_angle_

Definition at line 107 of file scan_shadows_filter.h.

◆ min_angle_

double laser_filters::ScanShadowsFilter::min_angle_

Definition at line 107 of file scan_shadows_filter.h.

◆ neighbors_

int laser_filters::ScanShadowsFilter::neighbors_

Definition at line 108 of file scan_shadows_filter.h.

◆ own_mutex_

boost::recursive_mutex laser_filters::ScanShadowsFilter::own_mutex_

Definition at line 114 of file scan_shadows_filter.h.

◆ param_config

ScanShadowsFilterConfig laser_filters::ScanShadowsFilter::param_config

Definition at line 115 of file scan_shadows_filter.h.

◆ remove_shadow_start_point_

bool laser_filters::ScanShadowsFilter::remove_shadow_start_point_

Definition at line 109 of file scan_shadows_filter.h.

◆ shadow_detector_

ScanShadowDetector laser_filters::ScanShadowsFilter::shadow_detector_

Definition at line 111 of file scan_shadows_filter.h.

◆ sin_map_

std::vector<float> laser_filters::ScanShadowsFilter::sin_map_
private

Definition at line 135 of file scan_shadows_filter.h.

◆ window_

int laser_filters::ScanShadowsFilter::window_

Definition at line 108 of file scan_shadows_filter.h.


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


laser_filters
Author(s): Tully Foote
autogenerated on Mon Apr 3 2023 02:51:57