sick_ldmrs_remove_background.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2016, DFKI GmbH
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of DFKI GmbH nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  *      Authors:
00030  *         Martin Günther <martin.guenther@dfki.de>
00031  *         Jochen Sprickerhof <ros@jochen.sprickerhof.de>
00032  *
00033  */
00034 
00035 #include <ros/ros.h>
00036 
00037 #include <pcl_conversions/pcl_conversions.h>
00038 
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <sick_ldmrs_msgs/sick_ldmrs_point_type.h>
00041 #include <pcl/point_cloud.h>
00042 
00043 typedef sick_ldmrs_msgs::SICK_LDMRS_Point PointT;
00044 typedef pcl::PointCloud<PointT> PointCloudT;
00045 
00046 ros::Publisher pub;
00047 ros::Publisher pub_bg;
00048 
00049 double min_dist_ratio_;
00050 
00051 PointCloudT::Ptr cloud_bg_;
00052 
00053 void callback(const sensor_msgs::PointCloud2::ConstPtr& pc)
00054 {
00055   PointCloudT::Ptr cloud = boost::make_shared<PointCloudT>();
00056   pcl::fromROSMsg(*pc, *cloud);
00057 
00058   if (!cloud->isOrganized())
00059   {
00060     ROS_ERROR_THROTTLE(15.0, "Input point cloud is not organized!");
00061     return;
00062   }
00063 
00064   if (cloud_bg_ && (cloud->width != cloud_bg_->width || cloud->height != cloud_bg_->height))
00065   {
00066     ROS_INFO("Dimensions of input cloud different from stored background, resetting background.");
00067     cloud_bg_.reset();
00068   }
00069 
00070   if (!cloud_bg_)
00071   {
00072     cloud_bg_ = cloud;
00073     return;
00074   }
00075 
00076   PointT invalid;
00077   invalid.x = invalid.y = invalid.z = std::numeric_limits<float>::quiet_NaN();
00078 //  PointCloudT::Ptr cloud_out = boost::make_shared<PointCloudT>(width, height, invalid);
00079 //  cloud_out->is_dense = false;
00080 
00081   for (size_t i = 0; i < cloud->size(); i++)
00082   {
00083     const PointT &p_in = cloud->points[i];
00084     const PointT &p_bg = cloud_bg_->points[i];
00085 
00086     // if input point invalid -> output invalid
00087     if (!pcl::isFinite<PointT>(p_in))
00088     {
00089       continue;
00090     }
00091 
00092     // if background invalid (and input valid) -> output valid
00093     if (!pcl::isFinite<PointT>(p_bg))
00094     {
00095       (*cloud_bg_)[i] = p_in;     // store new background point
00096       continue;
00097     }
00098 
00099     // compare ratio between background and input point to threshold
00100     float dist_in = p_in.getVector3fMap().norm();
00101     float dist_bg = p_bg.getVector3fMap().norm();
00102     float diff = dist_bg - dist_in;
00103 
00104     if (diff < 0)
00105     {
00106       // point is further away than previous background
00107       (*cloud_bg_)[i] = p_in;
00108       (*cloud)[i] = invalid;
00109     }
00110     else if (diff / dist_bg < min_dist_ratio_)
00111     {
00112       // point is too close to background
00113       (*cloud)[i] = invalid;
00114     }
00115 
00116     // ... otherwise, point is foreground => don't invalidate
00117   }
00118 
00119   sensor_msgs::PointCloud2::Ptr msg = boost::make_shared<sensor_msgs::PointCloud2>();
00120   pcl::toROSMsg(*cloud, *msg);
00121   msg->header = pc->header;
00122   pub.publish(msg);
00123 
00124   sensor_msgs::PointCloud2::Ptr msg_bg = boost::make_shared<sensor_msgs::PointCloud2>();
00125   pcl::toROSMsg(*cloud_bg_, *msg_bg);
00126   msg_bg->header = pc->header;
00127   pub_bg.publish(msg_bg);
00128 }
00129 
00130 int main(int argc, char **argv)
00131 {
00132   ros::init(argc, argv, "sick_ldmrs_remove_background");
00133   ros::NodeHandle nh;
00134   ros::NodeHandle private_nh("~");
00135 
00136   // min_dist_ratio: a point is filtered out if the distance between it and its
00137   // reference point is less than 5% of the distance between the sensor and the
00138   // reference point.
00139   min_dist_ratio_ = private_nh.param("min_dist_ratio", 0.05);
00140 
00141   ros::Subscriber sub = nh.subscribe("cloud", 10, callback);
00142   pub = nh.advertise<sensor_msgs::PointCloud2>("foreground", 10);
00143   pub_bg = nh.advertise<sensor_msgs::PointCloud2>("background", 10);
00144 
00145   ros::spin();
00146 
00147   return 0;
00148 }


sick_ldmrs_tools
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Mon Aug 14 2017 02:35:43