34 #ifndef LASER_PROC_ROS_H 35 #define LASER_PROC_ROS_H 39 #include <sensor_msgs/LaserScan.h> 40 #include <sensor_msgs/MultiEchoLaserScan.h> 41 #include <boost/thread/mutex.hpp> 54 void scanCb(
const sensor_msgs::MultiEchoLaserScanConstPtr& msg)
const;
laser_proc::LaserPublisher pub_
Publisher.
void disconnectCb(const ros::SingleSubscriberPublisher &pub)
void connectCb(const ros::SingleSubscriberPublisher &pub)
ros::NodeHandle nh_
Nodehandle used to subscribe in the connectCb.
LaserProcROS(ros::NodeHandle &n, ros::NodeHandle &pnh)
ros::Subscriber sub_
Multi echo subscriber.
void scanCb(const sensor_msgs::MultiEchoLaserScanConstPtr &msg) const
boost::mutex connect_mutex_
Prevents the connectCb and disconnectCb from being called until everything is initialized.