42 pub_ =
laser_proc::LaserTransport::advertiseLaser(n, 10, boost::bind(&
LaserProcROS::connectCb,
this, _1), boost::bind(&
LaserProcROS::disconnectCb,
this, _1),
ros::VoidPtr(),
false,
false);
58 ROS_DEBUG(
"Connecting to multi echo topic.");
66 ROS_DEBUG(
"Unsubscribing from multi echo topic.");
static LaserPublisher advertiseLaser(ros::NodeHandle &nh, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this LaserPublisher.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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.
void publish(const sensor_msgs::MultiEchoLaserScan &msg) const
Publish a MultiEchoLaserScan on the topics associated with this LaserPublisher.