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

This is a filter that removes points in a laser scan inside of a cartesian box. More...

#include <box_filter.h>

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

Public Member Functions

bool configure ()
 
 LaserScanBoxFilter ()
 
bool update (const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan)
 
- 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

bool inBox (tf::Point &point)
 
void reconfigureCB (BoxFilterConfig &config, uint32_t level)
 
- 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

std::string box_frame_
 
BoxFilterConfig config_ = BoxFilterConfig::__getDefault__()
 
std::shared_ptr< dynamic_reconfigure::Server< BoxFilterConfig > > dyn_server_
 
bool invert_filter
 
tf::Point max_
 
tf::Point min_
 
boost::recursive_mutex own_mutex_
 
laser_geometry::LaserProjection projector_
 
tf::TransformListener tf_
 
bool up_and_running_
 
- 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 cartesian box.

Definition at line 68 of file box_filter.h.

Constructor & Destructor Documentation

◆ LaserScanBoxFilter()

laser_filters::LaserScanBoxFilter::LaserScanBoxFilter ( )

Definition at line 48 of file box_filter.cpp.

Member Function Documentation

◆ configure()

bool laser_filters::LaserScanBoxFilter::configure ( )
virtual

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

Definition at line 53 of file box_filter.cpp.

◆ inBox()

bool laser_filters::LaserScanBoxFilter::inBox ( tf::Point point)
protected

Definition at line 176 of file box_filter.cpp.

◆ reconfigureCB()

void laser_filters::LaserScanBoxFilter::reconfigureCB ( BoxFilterConfig &  config,
uint32_t  level 
)
protected

Definition at line 183 of file box_filter.cpp.

◆ update()

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

Definition at line 80 of file box_filter.cpp.

Member Data Documentation

◆ box_frame_

std::string laser_filters::LaserScanBoxFilter::box_frame_
protected

Definition at line 80 of file box_filter.h.

◆ config_

BoxFilterConfig laser_filters::LaserScanBoxFilter::config_ = BoxFilterConfig::__getDefault__()
protected

Definition at line 94 of file box_filter.h.

◆ dyn_server_

std::shared_ptr<dynamic_reconfigure::Server<BoxFilterConfig> > laser_filters::LaserScanBoxFilter::dyn_server_
protected

Definition at line 91 of file box_filter.h.

◆ invert_filter

bool laser_filters::LaserScanBoxFilter::invert_filter
protected

Definition at line 88 of file box_filter.h.

◆ max_

tf::Point laser_filters::LaserScanBoxFilter::max_
protected

Definition at line 87 of file box_filter.h.

◆ min_

tf::Point laser_filters::LaserScanBoxFilter::min_
protected

Definition at line 87 of file box_filter.h.

◆ own_mutex_

boost::recursive_mutex laser_filters::LaserScanBoxFilter::own_mutex_
protected

Definition at line 93 of file box_filter.h.

◆ projector_

laser_geometry::LaserProjection laser_filters::LaserScanBoxFilter::projector_
protected

Definition at line 81 of file box_filter.h.

◆ tf_

tf::TransformListener laser_filters::LaserScanBoxFilter::tf_
protected

Definition at line 84 of file box_filter.h.

◆ up_and_running_

bool laser_filters::LaserScanBoxFilter::up_and_running_
protected

Definition at line 89 of file box_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