pointcloud_to_laserscan_nodelet.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010-2012, Willow Garage, Inc.
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
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *
00035  */
00036 
00037 /*
00038  * Author: Paul Bovbel
00039  */
00040 
00041 #include <pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet.h>
00042 #include <sensor_msgs/LaserScan.h>
00043 #include <pluginlib/class_list_macros.h>
00044 #include <sensor_msgs/point_cloud2_iterator.h>
00045 #include <tf2_sensor_msgs/tf2_sensor_msgs.h>
00046 
00047 namespace pointcloud_to_laserscan
00048 {
00049 
00050   PointCloudToLaserScanNodelet::PointCloudToLaserScanNodelet() {}
00051 
00052   void PointCloudToLaserScanNodelet::onInit()
00053   {
00054     boost::mutex::scoped_lock lock(connect_mutex_);
00055     private_nh_ = getPrivateNodeHandle();
00056 
00057     private_nh_.param<std::string>("target_frame", target_frame_, "");
00058     private_nh_.param<double>("transform_tolerance", tolerance_, 0.01);
00059     private_nh_.param<double>("min_height", min_height_, 0.0);
00060     private_nh_.param<double>("max_height", max_height_, 1.0);
00061 
00062     private_nh_.param<double>("angle_min", angle_min_, -M_PI / 2.0);
00063     private_nh_.param<double>("angle_max", angle_max_, M_PI / 2.0);
00064     private_nh_.param<double>("angle_increment", angle_increment_, M_PI / 360.0);
00065     private_nh_.param<double>("scan_time", scan_time_, 1.0 / 30.0);
00066     private_nh_.param<double>("range_min", range_min_, 0.45);
00067     private_nh_.param<double>("range_max", range_max_, 4.0);
00068 
00069     int concurrency_level;
00070     private_nh_.param<int>("concurrency_level", concurrency_level, 1);
00071     private_nh_.param<bool>("use_inf", use_inf_, true);
00072 
00073     //Check if explicitly single threaded, otherwise, let nodelet manager dictate thread pool size
00074     if (concurrency_level == 1)
00075     {
00076       nh_ = getNodeHandle();
00077     }
00078     else
00079     {
00080       nh_ = getMTNodeHandle();
00081     }
00082 
00083     // Only queue one pointcloud per running thread
00084     if (concurrency_level > 0)
00085     {
00086       input_queue_size_ = concurrency_level;
00087     }
00088     else
00089     {
00090       input_queue_size_ = boost::thread::hardware_concurrency();
00091     }
00092 
00093     // if pointcloud target frame specified, we need to filter by transform availability
00094     if (!target_frame_.empty())
00095     {
00096       tf2_.reset(new tf2_ros::Buffer());
00097       tf2_listener_.reset(new tf2_ros::TransformListener(*tf2_));
00098       message_filter_.reset(new MessageFilter(sub_, *tf2_, target_frame_, input_queue_size_, nh_));
00099       message_filter_->registerCallback(boost::bind(&PointCloudToLaserScanNodelet::cloudCb, this, _1));
00100       message_filter_->registerFailureCallback(boost::bind(&PointCloudToLaserScanNodelet::failureCb, this, _1, _2));
00101     }
00102     else // otherwise setup direct subscription
00103     {
00104       sub_.registerCallback(boost::bind(&PointCloudToLaserScanNodelet::cloudCb, this, _1));
00105     }
00106 
00107     pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan", 10,
00108                                                  boost::bind(&PointCloudToLaserScanNodelet::connectCb, this),
00109                                                  boost::bind(&PointCloudToLaserScanNodelet::disconnectCb, this));
00110   }
00111 
00112   void PointCloudToLaserScanNodelet::connectCb()
00113   {
00114     boost::mutex::scoped_lock lock(connect_mutex_);
00115     if (pub_.getNumSubscribers() > 0 && sub_.getSubscriber().getNumPublishers() == 0)
00116     {
00117       NODELET_INFO("Got a subscriber to scan, starting subscriber to pointcloud");
00118       sub_.subscribe(nh_, "cloud_in", input_queue_size_);
00119     }
00120   }
00121 
00122   void PointCloudToLaserScanNodelet::disconnectCb()
00123   {
00124     boost::mutex::scoped_lock lock(connect_mutex_);
00125     if (pub_.getNumSubscribers() == 0)
00126     {
00127       NODELET_INFO("No subscibers to scan, shutting down subscriber to pointcloud");
00128       sub_.unsubscribe();
00129     }
00130   }
00131 
00132   void PointCloudToLaserScanNodelet::failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg,
00133                                                tf2_ros::filter_failure_reasons::FilterFailureReason reason)
00134   {
00135     NODELET_WARN_STREAM_THROTTLE(1.0, "Can't transform pointcloud from frame " << cloud_msg->header.frame_id << " to "
00136         << message_filter_->getTargetFramesString());
00137   }
00138 
00139   void PointCloudToLaserScanNodelet::cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
00140   {
00141 
00142     //build laserscan output
00143     sensor_msgs::LaserScan output;
00144     output.header = cloud_msg->header;
00145     if (!target_frame_.empty())
00146     {
00147       output.header.frame_id = target_frame_;
00148     }
00149 
00150     output.angle_min = angle_min_;
00151     output.angle_max = angle_max_;
00152     output.angle_increment = angle_increment_;
00153     output.time_increment = 0.0;
00154     output.scan_time = scan_time_;
00155     output.range_min = range_min_;
00156     output.range_max = range_max_;
00157 
00158     //determine amount of rays to create
00159     uint32_t ranges_size = std::ceil((output.angle_max - output.angle_min) / output.angle_increment);
00160 
00161     //determine if laserscan rays with no obstacle data will evaluate to infinity or max_range
00162     if (use_inf_)
00163     {
00164       output.ranges.assign(ranges_size, std::numeric_limits<double>::infinity());
00165     }
00166     else
00167     {
00168       output.ranges.assign(ranges_size, output.range_max + 1.0);
00169     }
00170 
00171     sensor_msgs::PointCloud2ConstPtr cloud_out;
00172     sensor_msgs::PointCloud2Ptr cloud;
00173 
00174     // Transform cloud if necessary
00175     if (!(output.header.frame_id == cloud_msg->header.frame_id))
00176     {
00177       try
00178       {
00179         cloud.reset(new sensor_msgs::PointCloud2);
00180         tf2_->transform(*cloud_msg, *cloud, target_frame_, ros::Duration(tolerance_));
00181         cloud_out = cloud;
00182       }
00183       catch (tf2::TransformException ex)
00184       {
00185         NODELET_ERROR_STREAM("Transform failure: " << ex.what());
00186         return;
00187       }
00188     }
00189     else
00190     {
00191       cloud_out = cloud_msg;
00192     }
00193 
00194     // Iterate through pointcloud
00195     for (sensor_msgs::PointCloud2ConstIterator<float>
00196               iter_x(*cloud_out, "x"), iter_y(*cloud_out, "y"), iter_z(*cloud_out, "z");
00197               iter_x != iter_x.end();
00198               ++iter_x, ++iter_y, ++iter_z)
00199     {
00200 
00201       if (std::isnan(*iter_x) || std::isnan(*iter_y) || std::isnan(*iter_z))
00202       {
00203         NODELET_DEBUG("rejected for nan in point(%f, %f, %f)\n", *iter_x, *iter_y, *iter_z);
00204         continue;
00205       }
00206 
00207       if (*iter_z > max_height_ || *iter_z < min_height_)
00208       {
00209         NODELET_DEBUG("rejected for height %f not in range (%f, %f)\n", *iter_z, min_height_, max_height_);
00210         continue;
00211       }
00212 
00213       double range = hypot(*iter_x, *iter_y);
00214       if (range < range_min_)
00215       {
00216         NODELET_DEBUG("rejected for range %f below minimum value %f. Point: (%f, %f, %f)", range, range_min_, *iter_x, *iter_y,
00217                       *iter_z);
00218         continue;
00219       }
00220 
00221       double angle = atan2(*iter_y, *iter_x);
00222       if (angle < output.angle_min || angle > output.angle_max)
00223       {
00224         NODELET_DEBUG("rejected for angle %f not in range (%f, %f)\n", angle, output.angle_min, output.angle_max);
00225         continue;
00226       }
00227 
00228       //overwrite range at laserscan ray if new range is smaller
00229       int index = (angle - output.angle_min) / output.angle_increment;
00230       if (range < output.ranges[index])
00231       {
00232         output.ranges[index] = range;
00233       }
00234 
00235     }
00236     pub_.publish(output);
00237   }
00238 
00239 }
00240 
00241 PLUGINLIB_DECLARE_CLASS(pointcloud_to_laserscan, PointCloudToLaserScanNodelet, pointcloud_to_laserscan::PointCloudToLaserScanNodelet, nodelet::Nodelet);


pointcloud_to_laserscan
Author(s): Paul Bovbel , Tully Foote
autogenerated on Sat Jun 8 2019 19:51:08