laserscan_kinect_node.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <mutex>
4 
5 #include <ros/ros.h>
7 #include <sensor_msgs/Image.h>
8 #include <sensor_msgs/LaserScan.h>
9 #include <dynamic_reconfigure/server.h>
10 
11 #include <laserscan_kinect/LaserscanKinectConfig.h>
13 
14 namespace laserscan_kinect {
15 
17  public:
25 
26 private:
36  void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
37  const sensor_msgs::CameraInfoConstPtr& info_msg);
44  void connectCb();
50  void disconnectCb();
59  void reconfigureCb(laserscan_kinect::LaserscanKinectConfig &config, uint32_t level);
60 
72  dynamic_reconfigure::Server<laserscan_kinect::LaserscanKinectConfig> srv_;
76  std::mutex connect_mutex_;
77 };
78 
79 } // namespace laserscan_kinect
ros::NodeHandle pnh_
Private node handler used to generate the transport hints in the connectCb.
image_transport::ImageTransport it_
Subscribes to synchronized Image CameraInfo pairs.
LaserScanKinectNode(ros::NodeHandle &pnh)
LaserScanKinectNode constructor.
std::mutex connect_mutex_
Prevents the connectCb and disconnectCb from being called until everything is initialized.
void reconfigureCb(laserscan_kinect::LaserscanKinectConfig &config, uint32_t level)
reconfigureCb is dynamic reconfigure callback
void connectCb()
connectCb is callback which is called when new subscriber connected.
image_transport::Publisher pub_dbg_img_
Publisher for image_transport.
dynamic_reconfigure::Server< laserscan_kinect::LaserscanKinectConfig > srv_
Dynamic reconfigure server.
void disconnectCb()
disconnectCb is called when a subscriber stop subscribing
ros::Publisher pub_
Publisher for output LaserScan messages.
laserscan_kinect::LaserScanKinect converter_
Object which convert depth image to laserscan and store all parameters.
image_transport::CameraSubscriber sub_
Subscriber for image_transport.
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


laserscan_kinect
Author(s): Michal Drwiega (http://www.mdrwiega.com)
autogenerated on Wed May 5 2021 02:56:14