DepthImageToLaserScanROS.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Chad Rockey
32  */
33 
35 
36 using namespace depthimage_to_laserscan;
37 
39  boost::mutex::scoped_lock lock(connect_mutex_);
40 
41  // Dynamic Reconfigure
42  dynamic_reconfigure::Server<depthimage_to_laserscan::DepthConfig>::CallbackType f;
43  f = boost::bind(&DepthImageToLaserScanROS::reconfigureCb, this, _1, _2);
44  srv_.setCallback(f);
45 
46  // Lazy subscription to depth image topic
47  pub_ = n.advertise<sensor_msgs::LaserScan>("scan", 10, boost::bind(&DepthImageToLaserScanROS::connectCb, this, _1), boost::bind(&DepthImageToLaserScanROS::disconnectCb, this, _1));
48 }
49 
51  sub_.shutdown();
52 }
53 
54 
55 
56 void DepthImageToLaserScanROS::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
57  const sensor_msgs::CameraInfoConstPtr& info_msg){
58  try
59  {
60  sensor_msgs::LaserScanPtr scan_msg = dtl_.convert_msg(depth_msg, info_msg);
61  pub_.publish(scan_msg);
62  }
63  catch (std::runtime_error& e)
64  {
65  ROS_ERROR_THROTTLE(1.0, "Could not convert depth image to laserscan: %s", e.what());
66  }
67 }
68 
70  boost::mutex::scoped_lock lock(connect_mutex_);
71  if (!sub_ && pub_.getNumSubscribers() > 0) {
72  ROS_DEBUG("Connecting to depth topic.");
74  sub_ = it_.subscribeCamera("image", 10, &DepthImageToLaserScanROS::depthCb, this, hints);
75  }
76 }
77 
79  boost::mutex::scoped_lock lock(connect_mutex_);
80  if (pub_.getNumSubscribers() == 0) {
81  ROS_DEBUG("Unsubscribing from depth topic.");
82  sub_.shutdown();
83  }
84 }
85 
86 void DepthImageToLaserScanROS::reconfigureCb(depthimage_to_laserscan::DepthConfig& config, uint32_t level){
87  dtl_.set_scan_time(config.scan_time);
88  dtl_.set_range_limits(config.range_min, config.range_max);
89  dtl_.set_scan_height(config.scan_height);
90  dtl_.set_output_frame(config.output_frame_id);
91 }
image_transport::ImageTransport it_
Subscribes to synchronized Image CameraInfo pairs.
sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
void publish(const boost::shared_ptr< M > &message) const
f
boost::mutex connect_mutex_
Prevents the connectCb and disconnectCb from being called until everything is initialized.
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
image_transport::CameraSubscriber sub_
Subscriber for image_transport.
dynamic_reconfigure::Server< depthimage_to_laserscan::DepthConfig > srv_
Dynamic reconfigure server.
void set_output_frame(const std::string output_frame_id)
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
#define ROS_ERROR_THROTTLE(rate,...)
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)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
void disconnectCb(const ros::SingleSubscriberPublisher &pub)
void set_range_limits(const float range_min, const float range_max)
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)
#define ROS_DEBUG(...)


depthimage_to_laserscan
Author(s): Chad Rockey
autogenerated on Sun Jan 5 2020 03:45:46