| Public Member Functions | |
| void | callback (const sensor_msgs::LaserScan::ConstPtr &msg_in) | 
| void | deprecation_warn (const ros::TimerEvent &e) | 
| ScanToScanFilterChain () | |
| Protected Attributes | |
| ros::Timer | deprecation_timer_ | 
| filters::FilterChain < sensor_msgs::LaserScan > | filter_chain_ | 
| sensor_msgs::LaserScan | msg_ | 
| ros::NodeHandle | nh_ | 
| message_filters::Subscriber < sensor_msgs::LaserScan > | no_sub_ | 
| ros::Publisher | output_pub_ | 
| ros::NodeHandle | private_nh_ | 
| message_filters::Subscriber < sensor_msgs::LaserScan > | scan_sub_ | 
| tf::TransformListener | tf_ | 
| tf::MessageFilter < sensor_msgs::LaserScan > | tf_filter_ | 
| bool | using_filter_chain_deprecated_ | 
Definition at line 38 of file scan_to_scan_filter_chain.cpp.
| ScanToScanFilterChain::ScanToScanFilterChain | ( | ) |  [inline] | 
Definition at line 64 of file scan_to_scan_filter_chain.cpp.
| void ScanToScanFilterChain::callback | ( | const sensor_msgs::LaserScan::ConstPtr & | msg_in | ) |  [inline] | 
Definition at line 113 of file scan_to_scan_filter_chain.cpp.
| void ScanToScanFilterChain::deprecation_warn | ( | const ros::TimerEvent & | e | ) |  [inline] | 
Definition at line 106 of file scan_to_scan_filter_chain.cpp.
| ros::Timer ScanToScanFilterChain::deprecation_timer_  [protected] | 
Definition at line 59 of file scan_to_scan_filter_chain.cpp.
| filters::FilterChain<sensor_msgs::LaserScan> ScanToScanFilterChain::filter_chain_  [protected] | 
Definition at line 52 of file scan_to_scan_filter_chain.cpp.
| sensor_msgs::LaserScan ScanToScanFilterChain::msg_  [protected] | 
Definition at line 55 of file scan_to_scan_filter_chain.cpp.
| ros::NodeHandle ScanToScanFilterChain::nh_  [protected] | 
Definition at line 42 of file scan_to_scan_filter_chain.cpp.
| message_filters::Subscriber<sensor_msgs::LaserScan> ScanToScanFilterChain::no_sub_  [protected] | 
Definition at line 48 of file scan_to_scan_filter_chain.cpp.
| ros::Publisher ScanToScanFilterChain::output_pub_  [protected] | 
Definition at line 56 of file scan_to_scan_filter_chain.cpp.
| ros::NodeHandle ScanToScanFilterChain::private_nh_  [protected] | 
Definition at line 43 of file scan_to_scan_filter_chain.cpp.
| message_filters::Subscriber<sensor_msgs::LaserScan> ScanToScanFilterChain::scan_sub_  [protected] | 
Definition at line 47 of file scan_to_scan_filter_chain.cpp.
| tf::TransformListener ScanToScanFilterChain::tf_  [protected] | 
Definition at line 46 of file scan_to_scan_filter_chain.cpp.
| tf::MessageFilter<sensor_msgs::LaserScan> ScanToScanFilterChain::tf_filter_  [protected] | 
Definition at line 49 of file scan_to_scan_filter_chain.cpp.
| bool ScanToScanFilterChain::using_filter_chain_deprecated_  [protected] | 
Definition at line 60 of file scan_to_scan_filter_chain.cpp.