#include <laserscan_kinect_node.h>
Public Member Functions | |
LaserScanKinectNode (ros::NodeHandle &pnh) | |
LaserScanKinectNode constructor. More... | |
~LaserScanKinectNode () | |
Private Member Functions | |
void | connectCb () |
connectCb is callback which is called when new subscriber connected. More... | |
void | depthCb (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) |
depthCb is callback which is called when new depth image appear More... | |
void | disconnectCb () |
disconnectCb is called when a subscriber stop subscribing More... | |
void | reconfigureCb (laserscan_kinect::LaserscanKinectConfig &config, uint32_t level) |
reconfigureCb is dynamic reconfigure callback More... | |
Private Attributes | |
std::mutex | connect_mutex_ |
Prevents the connectCb and disconnectCb from being called until everything is initialized. More... | |
laserscan_kinect::LaserScanKinect | converter_ |
Object which convert depth image to laserscan and store all parameters. More... | |
image_transport::ImageTransport | it_ |
Subscribes to synchronized Image CameraInfo pairs. More... | |
ros::NodeHandle | pnh_ |
Private node handler used to generate the transport hints in the connectCb. More... | |
ros::Publisher | pub_ |
Publisher for output LaserScan messages. More... | |
image_transport::Publisher | pub_dbg_img_ |
Publisher for image_transport. More... | |
dynamic_reconfigure::Server< laserscan_kinect::LaserscanKinectConfig > | srv_ |
Dynamic reconfigure server. More... | |
image_transport::CameraSubscriber | sub_ |
Subscriber for image_transport. More... | |
Definition at line 16 of file laserscan_kinect_node.h.
laserscan_kinect::LaserScanKinectNode::LaserScanKinectNode | ( | ros::NodeHandle & | pnh | ) |
LaserScanKinectNode constructor.
pnh | Private node handler. |
Definition at line 7 of file laserscan_kinect_node.cpp.
laserscan_kinect::LaserScanKinectNode::~LaserScanKinectNode | ( | ) |
Definition at line 25 of file laserscan_kinect_node.cpp.
|
private |
connectCb is callback which is called when new subscriber connected.
It allow to subscribe depth image and publish laserscan message only when is laserscan subscriber appear.
Definition at line 48 of file laserscan_kinect_node.cpp.
|
private |
depthCb is callback which is called when new depth image appear
Callback for depth image and camera info. It converts depth image to laserscan and publishes it at the end.
depth_msg | Depth image provided by image_transport. |
info_msg | CameraInfo provided by image_transport. |
Definition at line 29 of file laserscan_kinect_node.cpp.
|
private |
disconnectCb is called when a subscriber stop subscribing
When no one subscribers subscribe laserscan topic, then it stop to subscribe depth image.
Definition at line 58 of file laserscan_kinect_node.cpp.
|
private |
reconfigureCb is dynamic reconfigure callback
Callback is necessary to set ROS parameters with dynamic reconfigure server.
config | Dynamic Reconfigure object. |
level | Dynamic Reconfigure level. |
Definition at line 67 of file laserscan_kinect_node.cpp.
|
private |
Prevents the connectCb and disconnectCb from being called until everything is initialized.
Definition at line 76 of file laserscan_kinect_node.h.
|
private |
Object which convert depth image to laserscan and store all parameters.
Definition at line 74 of file laserscan_kinect_node.h.
|
private |
Subscribes to synchronized Image CameraInfo pairs.
Definition at line 64 of file laserscan_kinect_node.h.
|
private |
Private node handler used to generate the transport hints in the connectCb.
Definition at line 62 of file laserscan_kinect_node.h.
|
private |
Publisher for output LaserScan messages.
Definition at line 68 of file laserscan_kinect_node.h.
|
private |
Publisher for image_transport.
Definition at line 70 of file laserscan_kinect_node.h.
|
private |
Dynamic reconfigure server.
Definition at line 72 of file laserscan_kinect_node.h.
|
private |
Subscriber for image_transport.
Definition at line 66 of file laserscan_kinect_node.h.