#include <LaserProcROS.h>
Public Member Functions | |
LaserProcROS (ros::NodeHandle &n, ros::NodeHandle &pnh) | |
~LaserProcROS () | |
Private Member Functions | |
void | connectCb (const ros::SingleSubscriberPublisher &pub) |
void | disconnectCb (const ros::SingleSubscriberPublisher &pub) |
void | scanCb (const sensor_msgs::MultiEchoLaserScanConstPtr &msg) const |
Private Attributes | |
boost::mutex | connect_mutex_ |
Prevents the connectCb and disconnectCb from being called until everything is initialized. | |
ros::NodeHandle | nh_ |
Nodehandle used to subscribe in the connectCb. | |
laser_proc::LaserPublisher | pub_ |
Publisher. | |
ros::Subscriber | sub_ |
Multi echo subscriber. |
Definition at line 45 of file LaserProcROS.h.
LaserProcROS::LaserProcROS | ( | ros::NodeHandle & | n, |
ros::NodeHandle & | pnh | ||
) |
Definition at line 38 of file LaserProcROS.cpp.
Definition at line 45 of file LaserProcROS.cpp.
void LaserProcROS::connectCb | ( | const ros::SingleSubscriberPublisher & | pub | ) | [private] |
Callback that is called when there is a new subscriber.
Will not subscribe until we have a subscriber for our LaserScans (lazy subscribing).
Definition at line 55 of file LaserProcROS.cpp.
void LaserProcROS::disconnectCb | ( | const ros::SingleSubscriberPublisher & | pub | ) | [private] |
Callback called when a subscriber unsubscribes.
If all current subscribers of our LaserScans stop listening, stop subscribing (lazy subscribing).
Definition at line 63 of file LaserProcROS.cpp.
void LaserProcROS::scanCb | ( | const sensor_msgs::MultiEchoLaserScanConstPtr & | msg | ) | const [private] |
Definition at line 51 of file LaserProcROS.cpp.
boost::mutex laser_proc::LaserProcROS::connect_mutex_ [private] |
Prevents the connectCb and disconnectCb from being called until everything is initialized.
Definition at line 76 of file LaserProcROS.h.
ros::NodeHandle laser_proc::LaserProcROS::nh_ [private] |
Nodehandle used to subscribe in the connectCb.
Definition at line 72 of file LaserProcROS.h.
Publisher.
Definition at line 73 of file LaserProcROS.h.
Multi echo subscriber.
Definition at line 74 of file LaserProcROS.h.