laserscan_to_pointcloud_nodelet.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Eurotec, Netherlands
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  *
35  */
36 
37 /*
38  * Author: Rein Appeldoorn
39  */
40 
42 #include <sensor_msgs/LaserScan.h>
45 #include <string>
47 
49 {
51 {
52 }
53 
55 {
56  boost::mutex::scoped_lock lock(connect_mutex_);
58 
59  private_nh_.param<std::string>("target_frame", target_frame_, "");
60  private_nh_.param<double>("transform_tolerance", transform_tolerance_, 0.01);
61 
62  int concurrency_level = private_nh_.param("concurrency_level", concurrency_level);
63 
64  // Check if explicitly single threaded, otherwise, let nodelet manager dictate thread pool size
65  if (concurrency_level == 1)
66  {
67  nh_ = getNodeHandle();
68  }
69  else
70  {
71  nh_ = getMTNodeHandle();
72  }
73 
74  // Only queue one pointcloud per running thread
75  if (concurrency_level > 0)
76  {
77  input_queue_size_ = static_cast<unsigned int>(concurrency_level);
78  }
79  else
80  {
81  input_queue_size_ = boost::thread::hardware_concurrency();
82  }
83 
84  // if pointcloud target frame specified, we need to filter by transform availability
85  if (!target_frame_.empty())
86  {
87  tf2_.reset(new tf2_ros::Buffer());
90  message_filter_->registerCallback(boost::bind(&LaserScanToPointCloudNodelet::scanCallback, this, _1));
91  message_filter_->registerFailureCallback(boost::bind(&LaserScanToPointCloudNodelet::failureCallback, this, _1, _2));
92  }
93  else // otherwise setup direct subscription
94  {
96  }
97 
98  pub_ =
99  nh_.advertise<sensor_msgs::PointCloud2>("cloud", 10, boost::bind(&LaserScanToPointCloudNodelet::connectCb, this),
100  boost::bind(&LaserScanToPointCloudNodelet::disconnectCb, this));
101 }
102 
104 {
105  boost::mutex::scoped_lock lock(connect_mutex_);
107  {
108  NODELET_INFO("Got a subscriber to cloud, starting laserscan subscriber");
109  sub_.subscribe(nh_, "scan_in", input_queue_size_);
110  }
111 }
112 
114 {
115  boost::mutex::scoped_lock lock(connect_mutex_);
116  if (pub_.getNumSubscribers() == 0)
117  {
118  NODELET_INFO("No subscibers to cloud, shutting down subscriber to laserscan");
119  sub_.unsubscribe();
120  }
121 }
122 
123 void LaserScanToPointCloudNodelet::failureCallback(const sensor_msgs::LaserScanConstPtr& scan_msg,
125 {
126  NODELET_WARN_STREAM_THROTTLE(1.0, "Can't transform laserscan from frame " << scan_msg->header.frame_id << " to "
127  << message_filter_->getTargetFramesString()
128  << " at time " << scan_msg->header.stamp
129  << ", reason: " << reason);
130 }
131 
132 void LaserScanToPointCloudNodelet::scanCallback(const sensor_msgs::LaserScanConstPtr& scan_msg)
133 {
134  sensor_msgs::PointCloud2Ptr scan_cloud;
135  scan_cloud.reset(new sensor_msgs::PointCloud2);
136  projector_.projectLaser(*scan_msg, *scan_cloud);
137 
138  // Transform cloud if necessary
139  if (!target_frame_.empty() && scan_cloud->header.frame_id != target_frame_)
140  {
141  try
142  {
143  *scan_cloud = tf2_->transform(*scan_cloud, target_frame_);
144  }
145  catch (tf2::TransformException& ex)
146  {
147  NODELET_ERROR_STREAM("Transform failure: " << ex.what());
148  return;
149  }
150  }
151  pub_.publish(*scan_cloud);
152 }
153 } // namespace pointcloud_to_laserscan
154 
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::message_filter_
boost::shared_ptr< MessageFilter > message_filter_
Definition: laserscan_to_pointcloud_nodelet.h:84
pointcloud_to_laserscan::LaserScanToPointCloudNodelet
The PointCloudToLaserScanNodelet class to process incoming laserscans into pointclouds.
Definition: laserscan_to_pointcloud_nodelet.h:61
NODELET_WARN_STREAM_THROTTLE
#define NODELET_WARN_STREAM_THROTTLE(rate,...)
point_cloud2_iterator.h
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::tf2_
boost::shared_ptr< tf2_ros::Buffer > tf2_
Definition: laserscan_to_pointcloud_nodelet.h:81
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::projector_
laser_geometry::LaserProjection projector_
Definition: laserscan_to_pointcloud_nodelet.h:86
tf2_ros::filter_failure_reasons::FilterFailureReason
FilterFailureReason
tf2_sensor_msgs.h
pointcloud_to_laserscan
Definition: laserscan_to_pointcloud_nodelet.h:55
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::target_frame_
std::string target_frame_
Definition: laserscan_to_pointcloud_nodelet.h:90
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::Subscriber::getNumPublishers
uint32_t getNumPublishers() const
tf2_ros::TransformListener
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::nh_
ros::NodeHandle nh_
Definition: laserscan_to_pointcloud_nodelet.h:76
class_list_macros.h
laser_geometry::LaserProjection::projectLaser
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
NODELET_ERROR_STREAM
#define NODELET_ERROR_STREAM(...)
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::scanCallback
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan_msg)
Definition: laserscan_to_pointcloud_nodelet.cpp:132
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::sub_
message_filters::Subscriber< sensor_msgs::LaserScan > sub_
Definition: laserscan_to_pointcloud_nodelet.h:83
tf2_ros::Buffer
message_filters::SimpleFilter::registerCallback
Connection registerCallback(const boost::function< void(P)> &callback)
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::connect_mutex_
boost::mutex connect_mutex_
Definition: laserscan_to_pointcloud_nodelet.h:79
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::private_nh_
ros::NodeHandle private_nh_
Definition: laserscan_to_pointcloud_nodelet.h:77
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::tf2_listener_
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
Definition: laserscan_to_pointcloud_nodelet.h:82
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::input_queue_size_
unsigned int input_queue_size_
Definition: laserscan_to_pointcloud_nodelet.h:89
laserscan_to_pointcloud_nodelet.h
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::pub_
ros::Publisher pub_
Definition: laserscan_to_pointcloud_nodelet.h:78
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
message_filters::Subscriber::getSubscriber
const ros::Subscriber & getSubscriber() const
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::disconnectCb
void disconnectCb()
Definition: laserscan_to_pointcloud_nodelet.cpp:113
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::onInit
virtual void onInit()
Definition: laserscan_to_pointcloud_nodelet.cpp:54
tf2::TransformException
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::connectCb
void connectCb()
Definition: laserscan_to_pointcloud_nodelet.cpp:103
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::failureCallback
void failureCallback(const sensor_msgs::LaserScanConstPtr &scan_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
Definition: laserscan_to_pointcloud_nodelet.cpp:123
pointcloud_to_laserscan::MessageFilter
tf2_ros::MessageFilter< sensor_msgs::LaserScan > MessageFilter
Definition: laserscan_to_pointcloud_nodelet.h:57
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::LaserScanToPointCloudNodelet
LaserScanToPointCloudNodelet()
Definition: laserscan_to_pointcloud_nodelet.cpp:50
nodelet::Nodelet::getMTNodeHandle
ros::NodeHandle & getMTNodeHandle() const
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::transform_tolerance_
double transform_tolerance_
Definition: laserscan_to_pointcloud_nodelet.h:91


pointcloud_to_laserscan
Author(s): Paul Bovbel , Tully Foote
autogenerated on Wed Mar 2 2022 00:44:25