39 #include <sensor_msgs/PointCloud2.h> 
   41 #include <pcl/point_cloud.h> 
   42 #include <pcl/common/point_tests.h> 
   54 void callback(
const sensor_msgs::PointCloud2::ConstPtr& pc)
 
   56   PointCloudT::Ptr cloud = pcl::make_shared<PointCloudT>();
 
   59   if (!cloud->isOrganized())
 
   67     ROS_INFO(
"Dimensions of input cloud different from stored background, resetting background.");
 
   78   invalid.x = invalid.y = invalid.z = std::numeric_limits<float>::quiet_NaN();
 
   82   for (
size_t i = 0; i < cloud->size(); i++)
 
   84     const PointT &p_in = cloud->points[i];
 
   88     if (!pcl::isFinite<PointT>(p_in))
 
   94     if (!pcl::isFinite<PointT>(p_bg))
 
   96       (*cloud_bg_)[i] = p_in;     
 
  101     float dist_in = p_in.getVector3fMap().norm();
 
  102     float dist_bg = p_bg.getVector3fMap().norm();
 
  103     float diff = dist_bg - dist_in;
 
  108       (*cloud_bg_)[i] = p_in;
 
  109       (*cloud)[i] = invalid;
 
  114       (*cloud)[i] = invalid;
 
  120   sensor_msgs::PointCloud2::Ptr 
msg = boost::make_shared<sensor_msgs::PointCloud2>();
 
  122   msg->header = pc->header;
 
  125   sensor_msgs::PointCloud2::Ptr msg_bg = boost::make_shared<sensor_msgs::PointCloud2>();
 
  127   msg_bg->header = pc->header;
 
  131 int main(
int argc, 
char **argv)
 
  133   ros::init(argc, argv, 
"sick_ldmrs_remove_background");
 
  143   pub = nh.
advertise<sensor_msgs::PointCloud2>(
"foreground", 10);