33 #ifndef VELODYNE_LASERSCAN_VELODYNE_LASERSCAN_H    34 #define VELODYNE_LASERSCAN_VELODYNE_LASERSCAN_H    37 #include <sensor_msgs/PointCloud2.h>    38 #include <sensor_msgs/LaserScan.h>    40 #include <boost/thread/mutex.hpp>    41 #include <boost/thread/lock_guard.hpp>    43 #include <dynamic_reconfigure/server.h>    44 #include <velodyne_laserscan/VelodyneLaserScanConfig.h>    57   void recvCallback(
const sensor_msgs::PointCloud2ConstPtr& msg);
    63   VelodyneLaserScanConfig 
cfg_;
    64   dynamic_reconfigure::Server<VelodyneLaserScanConfig> 
srv_;
    65   void reconfig(VelodyneLaserScanConfig& config, uint32_t level);
    72 #endif  // VELODYNE_LASERSCAN_VELODYNE_LASERSCAN_H 
boost::mutex connect_mutex_
VelodyneLaserScanConfig cfg_
dynamic_reconfigure::Server< VelodyneLaserScanConfig > srv_
VelodyneLaserScan(ros::NodeHandle &nh, ros::NodeHandle &nh_priv)
void recvCallback(const sensor_msgs::PointCloud2ConstPtr &msg)
void reconfig(VelodyneLaserScanConfig &config, uint32_t level)