Public Member Functions | Private Attributes | List of all members
laser_tilt_controller_filter::LaserTiltControllerFilter Class Reference

A filter that invalidates scans for certain periods of a tilt profile. More...

#include <laser_tilt_controller_filter.h>

Inheritance diagram for laser_tilt_controller_filter::LaserTiltControllerFilter:
Inheritance graph
[legend]

Public Member Functions

bool configure ()
 
 LaserTiltControllerFilter ()
 
bool loadFilterSignals ()
 
bool loadTiltProfileTiming ()
 
void signalCb (const pr2_msgs::LaserScannerSignal::ConstPtr &signal)
 
bool update (const sensor_msgs::LaserScan &scan_in, sensor_msgs::LaserScan &scan_out)
 
 ~LaserTiltControllerFilter ()
 
- 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 ()
 

Private Attributes

std::vector< int > filter_signals_
 
boost::mutex mutex_
 
bool signal_received_
 
ros::Subscriber signal_sub_
 
std::vector< double > tilt_profile_times_
 
ros::Time timer_zero_
 

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

A filter that invalidates scans for certain periods of a tilt profile.

Definition at line 50 of file laser_tilt_controller_filter.h.

Constructor & Destructor Documentation

laser_tilt_controller_filter::LaserTiltControllerFilter::LaserTiltControllerFilter ( )
inline

Definition at line 53 of file laser_tilt_controller_filter.h.

laser_tilt_controller_filter::LaserTiltControllerFilter::~LaserTiltControllerFilter ( )
inline

Definition at line 185 of file laser_tilt_controller_filter.h.

Member Function Documentation

bool laser_tilt_controller_filter::LaserTiltControllerFilter::configure ( )
inlinevirtual
bool laser_tilt_controller_filter::LaserTiltControllerFilter::loadFilterSignals ( )
inline

Definition at line 55 of file laser_tilt_controller_filter.h.

bool laser_tilt_controller_filter::LaserTiltControllerFilter::loadTiltProfileTiming ( )
inline

Definition at line 87 of file laser_tilt_controller_filter.h.

void laser_tilt_controller_filter::LaserTiltControllerFilter::signalCb ( const pr2_msgs::LaserScannerSignal::ConstPtr &  signal)
inline

Definition at line 132 of file laser_tilt_controller_filter.h.

bool laser_tilt_controller_filter::LaserTiltControllerFilter::update ( const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::LaserScan &  scan_out 
)
inlinevirtual

Member Data Documentation

std::vector<int> laser_tilt_controller_filter::LaserTiltControllerFilter::filter_signals_
private

Definition at line 188 of file laser_tilt_controller_filter.h.

boost::mutex laser_tilt_controller_filter::LaserTiltControllerFilter::mutex_
private

Definition at line 191 of file laser_tilt_controller_filter.h.

bool laser_tilt_controller_filter::LaserTiltControllerFilter::signal_received_
private

Definition at line 192 of file laser_tilt_controller_filter.h.

ros::Subscriber laser_tilt_controller_filter::LaserTiltControllerFilter::signal_sub_
private

Definition at line 193 of file laser_tilt_controller_filter.h.

std::vector<double> laser_tilt_controller_filter::LaserTiltControllerFilter::tilt_profile_times_
private

Definition at line 189 of file laser_tilt_controller_filter.h.

ros::Time laser_tilt_controller_filter::LaserTiltControllerFilter::timer_zero_
private

Definition at line 190 of file laser_tilt_controller_filter.h.


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


laser_tilt_controller_filter
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Jun 10 2019 14:28:40