DepthImageToLaserScanROS.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /* 
00031  * Author: Chad Rockey
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   // Dynamic Reconfigure
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   // Lazy subscription to depth image topic
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 }


depthimage_to_laserscan
Author(s): Chad Rockey
autogenerated on Tue Jan 7 2014 11:09:01