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
laser_geometry::LaserProjection projector_
unsigned int input_queue_size_
message_filters::Subscriber< sensor_msgs::LaserScan > sub_
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan_msg)
ros::NodeHandle private_nh_
std::string target_frame_
The PointCloudToLaserScanNodelet class to process incoming laserscans into pointclouds.
boost::shared_ptr< MessageFilter > message_filter_
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
boost::shared_ptr< tf2_ros::Buffer > tf2_
boost::mutex connect_mutex_
void failureCallback(const sensor_msgs::LaserScanConstPtr &scan_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
LaserScanToPointCloudNodelet()
double transform_tolerance_
tf2_ros::MessageFilter< sensor_msgs::LaserScan > MessageFilter