Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
laser_filters::StaticLaserScanPolygonFilter Class Reference

This is a filter that removes points in a laser scan inside of a polygon. It assumes that the transform between the scanner and the robot base remains unchanged, i.e. the position and orientation of the laser filter should not change. A typical use case for this filter is to filter out parts of the robot body or load that it may carry. More...

#include <polygon_filter.h>

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

Public Member Functions

bool configure () override
 
bool update (const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan) override
 
- Public Member Functions inherited from laser_filters::LaserScanPolygonFilterBase
virtual void configure (PolygonFilterConfig &config)
 
- 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 ()
 

Protected Member Functions

void reconfigureCB (laser_filters::PolygonFilterConfig &config, uint32_t level) override
 
- Protected Member Functions inherited from laser_filters::LaserScanPolygonFilterBase
bool inPolygon (tf::Point &point) const
 
void publishPolygon ()
 
- 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)
 

Private Member Functions

void checkCoSineMap (const sensor_msgs::LaserScan &input_scan)
 

Private Attributes

Eigen::ArrayXXd co_sine_map_
 
float co_sine_map_angle_max_
 
float co_sine_map_angle_min_
 
bool is_polygon_transformed_
 
double transform_timeout_
 

Additional Inherited Members

- Protected Attributes inherited from laser_filters::LaserScanPolygonFilterBase
std::shared_ptr< dynamic_reconfigure::Server< laser_filters::PolygonFilterConfig > > dyn_server_
 
bool invert_filter_
 
bool is_polygon_published_ = false
 
boost::recursive_mutex own_mutex_
 
geometry_msgs::Polygon polygon_
 
std::string polygon_frame_
 
double polygon_padding_
 
ros::Publisher polygon_pub_
 
- 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

This is a filter that removes points in a laser scan inside of a polygon. It assumes that the transform between the scanner and the robot base remains unchanged, i.e. the position and orientation of the laser filter should not change. A typical use case for this filter is to filter out parts of the robot body or load that it may carry.

Definition at line 107 of file polygon_filter.h.

Member Function Documentation

◆ checkCoSineMap()

void laser_filters::StaticLaserScanPolygonFilter::checkCoSineMap ( const sensor_msgs::LaserScan &  input_scan)
private

Definition at line 430 of file polygon_filter.cpp.

◆ configure()

bool laser_filters::StaticLaserScanPolygonFilter::configure ( )
overridevirtual

Reimplemented from laser_filters::LaserScanPolygonFilterBase.

Definition at line 420 of file polygon_filter.cpp.

◆ reconfigureCB()

void laser_filters::StaticLaserScanPolygonFilter::reconfigureCB ( laser_filters::PolygonFilterConfig &  config,
uint32_t  level 
)
overrideprotectedvirtual

Reimplemented from laser_filters::LaserScanPolygonFilterBase.

Definition at line 544 of file polygon_filter.cpp.

◆ update()

bool laser_filters::StaticLaserScanPolygonFilter::update ( const sensor_msgs::LaserScan &  input_scan,
sensor_msgs::LaserScan &  filtered_scan 
)
overridevirtual

Reimplemented from laser_filters::LaserScanPolygonFilterBase.

Definition at line 459 of file polygon_filter.cpp.

Member Data Documentation

◆ co_sine_map_

Eigen::ArrayXXd laser_filters::StaticLaserScanPolygonFilter::co_sine_map_
private

Definition at line 118 of file polygon_filter.h.

◆ co_sine_map_angle_max_

float laser_filters::StaticLaserScanPolygonFilter::co_sine_map_angle_max_
private

Definition at line 120 of file polygon_filter.h.

◆ co_sine_map_angle_min_

float laser_filters::StaticLaserScanPolygonFilter::co_sine_map_angle_min_
private

Definition at line 119 of file polygon_filter.h.

◆ is_polygon_transformed_

bool laser_filters::StaticLaserScanPolygonFilter::is_polygon_transformed_
private

Definition at line 121 of file polygon_filter.h.

◆ transform_timeout_

double laser_filters::StaticLaserScanPolygonFilter::transform_timeout_
private

Definition at line 116 of file polygon_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