34 #ifndef DEPTH_IMAGE_TO_LASERSCAN_ROS 35 #define DEPTH_IMAGE_TO_LASERSCAN_ROS 39 #include <sensor_msgs/Image.h> 40 #include <sensor_msgs/LaserScan.h> 41 #include <boost/thread/mutex.hpp> 42 #include <dynamic_reconfigure/server.h> 43 #include <depthimage_to_laserscan/DepthConfig.h> 66 void depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
67 const sensor_msgs::CameraInfoConstPtr& info_msg);
94 void reconfigureCb(depthimage_to_laserscan::DepthConfig& config, uint32_t level);
100 dynamic_reconfigure::Server<depthimage_to_laserscan::DepthConfig>
srv_;
image_transport::ImageTransport it_
Subscribes to synchronized Image CameraInfo pairs.
boost::mutex connect_mutex_
Prevents the connectCb and disconnectCb from being called until everything is initialized.
image_transport::CameraSubscriber sub_
Subscriber for image_transport.
dynamic_reconfigure::Server< depthimage_to_laserscan::DepthConfig > srv_
Dynamic reconfigure server.
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
ros::NodeHandle pnh_
Private nodehandle used to generate the transport hints in the connectCb.
ros::Publisher pub_
Publisher for output LaserScan messages.
void connectCb(const ros::SingleSubscriberPublisher &pub)
void disconnectCb(const ros::SingleSubscriberPublisher &pub)
~DepthImageToLaserScanROS()
depthimage_to_laserscan::DepthImageToLaserScan dtl_
Instance of the DepthImageToLaserScan conversion class.
DepthImageToLaserScanROS(ros::NodeHandle &n, ros::NodeHandle &pnh)
void reconfigureCb(depthimage_to_laserscan::DepthConfig &config, uint32_t level)