Go to the documentation of this file.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 #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
00079
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
00087 if (!pcl::isFinite<PointT>(p_in))
00088 {
00089 continue;
00090 }
00091
00092
00093 if (!pcl::isFinite<PointT>(p_bg))
00094 {
00095 (*cloud_bg_)[i] = p_in;
00096 continue;
00097 }
00098
00099
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
00107 (*cloud_bg_)[i] = p_in;
00108 (*cloud)[i] = invalid;
00109 }
00110 else if (diff / dist_bg < min_dist_ratio_)
00111 {
00112
00113 (*cloud)[i] = invalid;
00114 }
00115
00116
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
00137
00138
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 }