Go to the documentation of this file.
41 #ifndef POINTCLOUD_TO_LASERSCAN_LASERSCAN_TO_POINTCLOUD_NODELET_H
42 #define POINTCLOUD_TO_LASERSCAN_LASERSCAN_TO_POINTCLOUD_NODELET_H
44 #include <boost/thread/mutex.hpp>
49 #include <sensor_msgs/LaserScan.h>
69 void scanCallback(
const sensor_msgs::LaserScanConstPtr& scan_msg);
96 #endif // POINTCLOUD_TO_LASERSCAN_LASERSCAN_TO_POINTCLOUD_NODELET_H
boost::shared_ptr< MessageFilter > message_filter_
The PointCloudToLaserScanNodelet class to process incoming laserscans into pointclouds.
boost::shared_ptr< tf2_ros::Buffer > tf2_
laser_geometry::LaserProjection projector_
std::string target_frame_
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan_msg)
message_filters::Subscriber< sensor_msgs::LaserScan > sub_
boost::mutex connect_mutex_
ros::NodeHandle private_nh_
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
unsigned int input_queue_size_
void failureCallback(const sensor_msgs::LaserScanConstPtr &scan_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
tf2_ros::MessageFilter< sensor_msgs::LaserScan > MessageFilter
LaserScanToPointCloudNodelet()
double transform_tolerance_