#include <DepthImageToLaserScanROS.h>
Public Member Functions | |
DepthImageToLaserScanROS (ros::NodeHandle &n, ros::NodeHandle &pnh) | |
~DepthImageToLaserScanROS () | |
Private Member Functions | |
void | connectCb (const ros::SingleSubscriberPublisher &pub) |
void | depthCb (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) |
void | disconnectCb (const ros::SingleSubscriberPublisher &pub) |
void | reconfigureCb (depthimage_to_laserscan::DepthConfig &config, uint32_t level) |
Private Attributes | |
boost::mutex | connect_mutex_ |
Prevents the connectCb and disconnectCb from being called until everything is initialized. More... | |
depthimage_to_laserscan::DepthImageToLaserScan | dtl_ |
Instance of the DepthImageToLaserScan conversion class. More... | |
image_transport::ImageTransport | it_ |
Subscribes to synchronized Image CameraInfo pairs. More... | |
ros::NodeHandle | pnh_ |
Private nodehandle used to generate the transport hints in the connectCb. More... | |
ros::Publisher | pub_ |
Publisher for output LaserScan messages. More... | |
dynamic_reconfigure::Server< depthimage_to_laserscan::DepthConfig > | srv_ |
Dynamic reconfigure server. More... | |
image_transport::CameraSubscriber | sub_ |
Subscriber for image_transport. More... | |
Definition at line 49 of file DepthImageToLaserScanROS.h.
DepthImageToLaserScanROS::DepthImageToLaserScanROS | ( | ros::NodeHandle & | n, |
ros::NodeHandle & | pnh | ||
) |
Definition at line 38 of file DepthImageToLaserScanROS.cpp.
DepthImageToLaserScanROS::~DepthImageToLaserScanROS | ( | ) |
Definition at line 50 of file DepthImageToLaserScanROS.cpp.
|
private |
Callback that is called when there is a new subscriber.
Will not subscribe to the image and camera_info until we have a subscriber for our LaserScan (lazy subscribing).
Definition at line 69 of file DepthImageToLaserScanROS.cpp.
|
private |
Callback for image_transport
Synchronized callback for depth image and camera info. Publishes laserscan at the end of this callback.
depth_msg | Image provided by image_transport. |
info_msg | CameraInfo provided by image_transport. |
Definition at line 56 of file DepthImageToLaserScanROS.cpp.
|
private |
Callback called when a subscriber unsubscribes.
If all current subscribers of our LaserScan stop listening, stop subscribing (lazy subscribing).
Definition at line 78 of file DepthImageToLaserScanROS.cpp.
|
private |
Dynamic reconfigure callback.
Callback that is used to set each of the parameters insde the DepthImageToLaserScan object.
config | Dynamic Reconfigure object. |
level | Dynamic Reconfigure level. |
Definition at line 86 of file DepthImageToLaserScanROS.cpp.
|
private |
Prevents the connectCb and disconnectCb from being called until everything is initialized.
Definition at line 104 of file DepthImageToLaserScanROS.h.
|
private |
Instance of the DepthImageToLaserScan conversion class.
Definition at line 102 of file DepthImageToLaserScanROS.h.
|
private |
Subscribes to synchronized Image CameraInfo pairs.
Definition at line 97 of file DepthImageToLaserScanROS.h.
|
private |
Private nodehandle used to generate the transport hints in the connectCb.
Definition at line 96 of file DepthImageToLaserScanROS.h.
|
private |
Publisher for output LaserScan messages.
Definition at line 99 of file DepthImageToLaserScanROS.h.
|
private |
Dynamic reconfigure server.
Definition at line 100 of file DepthImageToLaserScanROS.h.
|
private |
Subscriber for image_transport.
Definition at line 98 of file DepthImageToLaserScanROS.h.