Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <depthimage_to_laserscan/DepthImageToLaserScanROS.h>
00035
00036 using namespace depthimage_to_laserscan;
00037
00038 DepthImageToLaserScanROS::DepthImageToLaserScanROS(ros::NodeHandle& n, ros::NodeHandle& pnh):pnh_(pnh), it_(n), srv_(pnh) {
00039 boost::mutex::scoped_lock lock(connect_mutex_);
00040
00041
00042 dynamic_reconfigure::Server<depthimage_to_laserscan::DepthConfig>::CallbackType f;
00043 f = boost::bind(&DepthImageToLaserScanROS::reconfigureCb, this, _1, _2);
00044 srv_.setCallback(f);
00045
00046
00047 pub_ = n.advertise<sensor_msgs::LaserScan>("scan", 10, boost::bind(&DepthImageToLaserScanROS::connectCb, this, _1), boost::bind(&DepthImageToLaserScanROS::disconnectCb, this, _1));
00048 }
00049
00050 DepthImageToLaserScanROS::~DepthImageToLaserScanROS(){
00051 sub_.shutdown();
00052 }
00053
00054
00055
00056 void DepthImageToLaserScanROS::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00057 const sensor_msgs::CameraInfoConstPtr& info_msg){
00058 try
00059 {
00060 sensor_msgs::LaserScanPtr scan_msg = dtl_.convert_msg(depth_msg, info_msg);
00061 pub_.publish(scan_msg);
00062 }
00063 catch (std::runtime_error& e)
00064 {
00065 ROS_ERROR_THROTTLE(1.0, "Could not convert depth image to laserscan: %s", e.what());
00066 }
00067 }
00068
00069 void DepthImageToLaserScanROS::connectCb(const ros::SingleSubscriberPublisher& pub) {
00070 boost::mutex::scoped_lock lock(connect_mutex_);
00071 if (!sub_ && pub_.getNumSubscribers() > 0) {
00072 ROS_DEBUG("Connecting to depth topic.");
00073 image_transport::TransportHints hints("raw", ros::TransportHints(), pnh_);
00074 sub_ = it_.subscribeCamera("image", 10, &DepthImageToLaserScanROS::depthCb, this, hints);
00075 }
00076 }
00077
00078 void DepthImageToLaserScanROS::disconnectCb(const ros::SingleSubscriberPublisher& pub) {
00079 boost::mutex::scoped_lock lock(connect_mutex_);
00080 if (pub_.getNumSubscribers() == 0) {
00081 ROS_DEBUG("Unsubscribing from depth topic.");
00082 sub_.shutdown();
00083 }
00084 }
00085
00086 void DepthImageToLaserScanROS::reconfigureCb(depthimage_to_laserscan::DepthConfig& config, uint32_t level){
00087 dtl_.set_scan_time(config.scan_time);
00088 dtl_.set_range_limits(config.range_min, config.range_max);
00089 dtl_.set_scan_height(config.scan_height);
00090 dtl_.set_output_frame(config.output_frame_id);
00091 }