#include <laserscan_kinect_node.h>
Public Member Functions | |
| LaserScanKinectNode (ros::NodeHandle &n, ros::NodeHandle &pnh) | |
| LaserScanKinectNode constructor. | |
| ~LaserScanKinectNode () | |
Private Member Functions | |
| void | connectCb (const ros::SingleSubscriberPublisher &pub) |
| connectCb is callback which is called when new subscriber connected. | |
| 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 | |
| void | disconnectCb (const ros::SingleSubscriberPublisher &pub) |
| disconnectCb is called when a subscriber stop subscribing | |
| void | reconfigureCb (laserscan_kinect::LaserscanKinectConfig &config, uint32_t level) |
| reconfigureCb is dynamic reconfigure callback | |
Private Attributes | |
| boost::mutex | connect_mutex_ |
| Prevents the connectCb and disconnectCb from being called until everything is initialized. | |
| laserscan_kinect::LaserScanKinect | converter_ |
| Object which convert depth image to laserscan and store all parameters. | |
| image_transport::ImageTransport | it_ |
| Subscribes to synchronized Image CameraInfo pairs. | |
| ros::NodeHandle | pnh_ |
| Private node handler used to generate the transport hints in the connectCb. | |
| ros::Publisher | pub_ |
| Publisher for output LaserScan messages. | |
| dynamic_reconfigure::Server < laserscan_kinect::LaserscanKinectConfig > | srv_ |
| Dynamic reconfigure server. | |
| image_transport::CameraSubscriber | sub_ |
| Subscriber for image_transport. | |
Definition at line 52 of file laserscan_kinect_node.h.
LaserScanKinectNode constructor.
| n | Node handler. |
| pnh | Private node handler. |
Definition at line 42 of file laserscan_kinect_node.cpp.
Definition at line 57 of file laserscan_kinect_node.cpp.
| void LaserScanKinectNode::connectCb | ( | const ros::SingleSubscriberPublisher & | pub | ) | [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.
| pub | Publisher which subscribers are checked. |
Definition at line 78 of file laserscan_kinect_node.cpp.
| void LaserScanKinectNode::depthCb | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |
| const sensor_msgs::CameraInfoConstPtr & | info_msg | ||
| ) | [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 63 of file laserscan_kinect_node.cpp.
| void LaserScanKinectNode::disconnectCb | ( | const ros::SingleSubscriberPublisher & | pub | ) | [private] |
disconnectCb is called when a subscriber stop subscribing
When no one subscribers subscribe laserscan topic, then it stop to subscribe depth image.
| pub | Publisher which subscribers are checked. |
Definition at line 90 of file laserscan_kinect_node.cpp.
| void LaserScanKinectNode::reconfigureCb | ( | laserscan_kinect::LaserscanKinectConfig & | config, |
| uint32_t | level | ||
| ) | [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 101 of file laserscan_kinect_node.cpp.
boost::mutex laserscan_kinect::LaserScanKinectNode::connect_mutex_ [private] |
Prevents the connectCb and disconnectCb from being called until everything is initialized.
Definition at line 116 of file laserscan_kinect_node.h.
Object which convert depth image to laserscan and store all parameters.
Definition at line 114 of file laserscan_kinect_node.h.
Subscribes to synchronized Image CameraInfo pairs.
Definition at line 106 of file laserscan_kinect_node.h.
Private node handler used to generate the transport hints in the connectCb.
Definition at line 104 of file laserscan_kinect_node.h.
Publisher for output LaserScan messages.
Definition at line 110 of file laserscan_kinect_node.h.
dynamic_reconfigure::Server<laserscan_kinect::LaserscanKinectConfig> laserscan_kinect::LaserScanKinectNode::srv_ [private] |
Dynamic reconfigure server.
Definition at line 112 of file laserscan_kinect_node.h.
Subscriber for image_transport.
Definition at line 108 of file laserscan_kinect_node.h.