00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 #include <pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet.h>
00042 #include <nodelet/nodelet.h>
00043 #include <sensor_msgs/LaserScan.h>
00044 #include <pcl_ros/transforms.h>
00045 #include <math.h>
00046 #include <pluginlib/class_list_macros.h>
00047 
00048 namespace pointcloud_to_laserscan
00049 {
00050 
00051   void PointCloudToLaserScanNodelet::onInit()
00052   {
00053       nh_ = getMTNodeHandle();
00054       private_nh_ = getMTPrivateNodeHandle();
00055 
00056       private_nh_.param<std::string>("target_frame", target_frame_, "");
00057       private_nh_.param<double>("min_height", min_height_, 0.0);
00058       private_nh_.param<double>("max_height", max_height_, 1.0);
00059 
00060       private_nh_.param<double>("angle_min", angle_min_, -M_PI/2.0);
00061       private_nh_.param<double>("angle_max", angle_max_, M_PI/2.0);
00062       private_nh_.param<double>("angle_increment", angle_increment_, M_PI/360.0);
00063       private_nh_.param<double>("scan_time", scan_time_, 1.0/30.0);
00064       private_nh_.param<double>("range_min", range_min_, 0.45);
00065       private_nh_.param<double>("range_max", range_max_, 4.0);
00066 
00067       int concurrency_level;
00068       private_nh_.param<int>("concurrency_level", concurrency_level, 1);
00069       private_nh_.param<bool>("use_inf", use_inf_, true);
00070 
00071       boost::mutex::scoped_lock lock(connect_mutex_);
00072 
00073       
00074       if(concurrency_level > 0)
00075       {
00076           input_queue_size_ = concurrency_level;
00077       }else{
00078           input_queue_size_ = boost::thread::hardware_concurrency();
00079       }
00080 
00081       pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan", 10,
00082           boost::bind(&PointCloudToLaserScanNodelet::connectCb, this),
00083           boost::bind(&PointCloudToLaserScanNodelet::disconnectCb, this));
00084   }
00085 
00086   void PointCloudToLaserScanNodelet::connectCb()
00087   {
00088       boost::mutex::scoped_lock lock(connect_mutex_);
00089       if (!sub_ && pub_.getNumSubscribers() > 0) {
00090           NODELET_DEBUG("Connecting to depth topic.");
00091           sub_ = nh_.subscribe("cloud_in", input_queue_size_, &PointCloudToLaserScanNodelet::cloudCb, this);
00092       }
00093   }
00094 
00095   void PointCloudToLaserScanNodelet::disconnectCb()
00096   {
00097       boost::mutex::scoped_lock lock(connect_mutex_);
00098       if (pub_.getNumSubscribers() == 0) {
00099           NODELET_DEBUG("Unsubscribing from depth topic.");
00100           sub_.shutdown();
00101       }
00102   }
00103 
00104   void PointCloudToLaserScanNodelet::cloudCb(const PointCloud::ConstPtr &cloud_msg)
00105   {
00106       
00107       PointCloud::ConstPtr cloud_scan;
00108 
00109       std_msgs::Header cloud_header = pcl_conversions::fromPCL(cloud_msg->header);
00110 
00111       
00112       sensor_msgs::LaserScan output;
00113       output.header = cloud_header;
00114       output.angle_min = angle_min_;
00115       output.angle_max = angle_max_;
00116       output.angle_increment = angle_increment_;
00117       output.time_increment = 0.0;
00118       output.scan_time = scan_time_;
00119       output.range_min = range_min_;
00120       output.range_max = range_max_;
00121 
00122       
00123       if(!target_frame_.empty() && cloud_header.frame_id != target_frame_){
00124           output.header.frame_id = target_frame_;
00125 
00126           if(tf_.waitForTransform(cloud_header.frame_id, target_frame_, cloud_header.stamp, ros::Duration(10.0))){
00127               PointCloud::Ptr cloud_tf(new PointCloud);
00128               pcl_ros::transformPointCloud(target_frame_, *cloud_msg, *cloud_tf, tf_);
00129               cloud_scan = cloud_tf;
00130           }else{
00131               NODELET_WARN_STREAM_THROTTLE(1.0, "Can't transform cloud with frame " << cloud_header.frame_id << " into "
00132                   "lasercan with frame " << target_frame_);
00133               return;
00134           }
00135       }else{
00136           cloud_scan = cloud_msg;
00137       }
00138 
00139       
00140       uint32_t ranges_size = std::ceil((output.angle_max - output.angle_min) / output.angle_increment);
00141 
00142       
00143       if(use_inf_){
00144           output.ranges.assign(ranges_size, std::numeric_limits<double>::infinity());
00145       }else{
00146           output.ranges.assign(ranges_size, output.range_max + 1.0);
00147       }
00148 
00149       for (PointCloud::const_iterator it = cloud_scan->begin(); it != cloud_scan->end(); ++it){
00150           const float &x = it->x;
00151           const float &y = it->y;
00152           const float &z = it->z;
00153 
00154           if ( std::isnan(x) || std::isnan(y) || std::isnan(z) ){
00155               NODELET_DEBUG("rejected for nan in point(%f, %f, %f)\n", x, y, z);
00156               continue;
00157           }
00158 
00159           if (z > max_height_ || z < min_height_){
00160               NODELET_DEBUG("rejected for height %f not in range (%f, %f)\n", z, min_height_, max_height_);
00161               continue;
00162           }
00163 
00164           double range = hypot(x,y);
00165           if (range < range_min_){
00166               NODELET_DEBUG("rejected for range %f below minimum value %f. Point: (%f, %f, %f)", range, range_min_, x, y, z);
00167               continue;
00168           }
00169 
00170           double angle = atan2(y, x);
00171           if (angle < output.angle_min || angle > output.angle_max){
00172               NODELET_DEBUG("rejected for angle %f not in range (%f, %f)\n", angle, output.angle_min, output.angle_max);
00173               continue;
00174           }
00175 
00176           
00177           int index = (angle - output.angle_min) / output.angle_increment;
00178           if (range < output.ranges[index]){
00179               output.ranges[index] = range;
00180           }
00181       }
00182       pub_.publish(output);
00183   }
00184 
00185 }
00186 
00187 PLUGINLIB_DECLARE_CLASS(pointcloud_to_laserscan, PointCloudToLaserScanNodelet, pointcloud_to_laserscan::PointCloudToLaserScanNodelet, nodelet::Nodelet);
00188