laserscan_kinect_node.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2015, Michal Drwiega (drwiega.michal@gmail.com)
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *     1. Redistributions of source code must retain the above copyright
00010  *        notice, this list of conditions and the following disclaimer.
00011  *     2. Redistributions in binary form must reproduce the above copyright
00012  *        notice, this list of conditions and the following disclaimer in the
00013  *        documentation and/or other materials provided with the distribution.
00014  *     3. Neither the name of the copyright holder nor the names of its
00015  *        contributors may be used to endorse or promote products derived
00016  *        from this software without specific prior written permission.
00017  *
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
00021  * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
00022  * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
00023  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
00024  * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
00025  * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00026  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
00027  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029  *****************************************************************************/
00037 #include <laserscan_kinect/laserscan_kinect_node.h>
00038 
00039 using namespace laserscan_kinect;
00040 
00041 //=================================================================================================
00042 LaserScanKinectNode::LaserScanKinectNode(ros::NodeHandle& n, ros::NodeHandle& pnh) :
00043   pnh_(pnh), it_(n), srv_(pnh)
00044 {
00045   boost::mutex::scoped_lock lock(connect_mutex_);
00046 
00047   // Dynamic reconfigure server callback
00048   srv_.setCallback(boost::bind(&LaserScanKinectNode::reconfigureCb, this, _1, _2));
00049   
00050   // Subscription to depth image topic
00051   pub_ = n.advertise<sensor_msgs::LaserScan>("scan", 10,
00052                                              boost::bind(&LaserScanKinectNode::connectCb, this, _1),
00053                                              boost::bind(&LaserScanKinectNode::disconnectCb, this, _1));
00054 }
00055 
00056 //=================================================================================================
00057 LaserScanKinectNode::~LaserScanKinectNode()
00058 {
00059   sub_.shutdown();
00060 }
00061 
00062 //=================================================================================================
00063 void LaserScanKinectNode::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00064                                   const sensor_msgs::CameraInfoConstPtr& info_msg)
00065 {
00066   try
00067   {
00068     sensor_msgs::LaserScanPtr laserscan_msg = converter_.prepareLaserScanMsg(depth_msg, info_msg);
00069     pub_.publish(laserscan_msg);
00070   }
00071   catch (std::runtime_error& e)
00072   {
00073     ROS_ERROR_THROTTLE(1.0, "Could not convert depth image to laserscan: %s", e.what());
00074   }
00075 }
00076 
00077 //=================================================================================================
00078 void LaserScanKinectNode::connectCb(const ros::SingleSubscriberPublisher& pub)
00079 {
00080   boost::mutex::scoped_lock lock(connect_mutex_);
00081   if (!sub_ && pub_.getNumSubscribers() > 0)
00082   {
00083     ROS_DEBUG("Connecting to depth topic.");
00084     image_transport::TransportHints hints("raw", ros::TransportHints(), pnh_);
00085     sub_ = it_.subscribeCamera("image", 10, &LaserScanKinectNode::depthCb, this, hints);
00086   }
00087 }
00088 
00089 //=================================================================================================
00090 void LaserScanKinectNode::disconnectCb(const ros::SingleSubscriberPublisher& pub)
00091 {
00092   boost::mutex::scoped_lock lock(connect_mutex_);
00093   if (pub_.getNumSubscribers() == 0)
00094   {
00095     ROS_DEBUG("Unsubscribing from depth topic.");
00096     sub_.shutdown();
00097   }
00098 }
00099 
00100 //=================================================================================================
00101 void LaserScanKinectNode::reconfigureCb(laserscan_kinect::LaserscanKinectConfig& config,
00102                                         uint32_t level)
00103 {
00104   converter_.setOutputFrame(config.output_frame_id);
00105   converter_.setRangeLimits(config.range_min, config.range_max);
00106   converter_.setScanHeight(config.scan_height);
00107   converter_.setDepthImgRowStep(config.depth_img_row_step);
00108   converter_.setCamModelUpdate(config.cam_model_update);
00109 
00110   converter_.setSensorMountHeight(config.sensor_mount_height);
00111   converter_.setSensorTiltAngle(config.sensor_tilt_angle);
00112   converter_.setGroundRemove(config.ground_remove_en);
00113   converter_.setGroundMargin(config.ground_margin);
00114   converter_.setTiltCompensation(config.tilt_compensation_en);
00115 
00116   converter_.setScanConfigurated(false);
00117 }
00118 
00119 //=================================================================================================
00120 //=================================================================================================


laserscan_kinect
Author(s): Michal Drwiega
autogenerated on Thu Jun 6 2019 22:10:52