sick_ldmrs_remove_background.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016, DFKI GmbH
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of DFKI GmbH nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Authors:
30  * Martin Günther <martin.guenther@dfki.de>
31  * Jochen Sprickerhof <ros@jochen.sprickerhof.de>
32  *
33  */
34 
35 #include <ros/ros.h>
36 
38 
39 #include <sensor_msgs/PointCloud2.h>
41 #include <pcl/point_cloud.h>
42 
44 typedef pcl::PointCloud<PointT> PointCloudT;
45 
48 
50 
51 PointCloudT::Ptr cloud_bg_;
52 
53 void callback(const sensor_msgs::PointCloud2::ConstPtr& pc)
54 {
55  PointCloudT::Ptr cloud = boost::make_shared<PointCloudT>();
56  pcl::fromROSMsg(*pc, *cloud);
57 
58  if (!cloud->isOrganized())
59  {
60  ROS_ERROR_THROTTLE(15.0, "Input point cloud is not organized!");
61  return;
62  }
63 
64  if (cloud_bg_ && (cloud->width != cloud_bg_->width || cloud->height != cloud_bg_->height))
65  {
66  ROS_INFO("Dimensions of input cloud different from stored background, resetting background.");
67  cloud_bg_.reset();
68  }
69 
70  if (!cloud_bg_)
71  {
72  cloud_bg_ = cloud;
73  return;
74  }
75 
76  PointT invalid;
77  invalid.x = invalid.y = invalid.z = std::numeric_limits<float>::quiet_NaN();
78 // PointCloudT::Ptr cloud_out = boost::make_shared<PointCloudT>(width, height, invalid);
79 // cloud_out->is_dense = false;
80 
81  for (size_t i = 0; i < cloud->size(); i++)
82  {
83  const PointT &p_in = cloud->points[i];
84  const PointT &p_bg = cloud_bg_->points[i];
85 
86  // if input point invalid -> output invalid
87  if (!pcl::isFinite<PointT>(p_in))
88  {
89  continue;
90  }
91 
92  // if background invalid (and input valid) -> output valid
93  if (!pcl::isFinite<PointT>(p_bg))
94  {
95  (*cloud_bg_)[i] = p_in; // store new background point
96  continue;
97  }
98 
99  // compare ratio between background and input point to threshold
100  float dist_in = p_in.getVector3fMap().norm();
101  float dist_bg = p_bg.getVector3fMap().norm();
102  float diff = dist_bg - dist_in;
103 
104  if (diff < 0)
105  {
106  // point is further away than previous background
107  (*cloud_bg_)[i] = p_in;
108  (*cloud)[i] = invalid;
109  }
110  else if (diff / dist_bg < min_dist_ratio_)
111  {
112  // point is too close to background
113  (*cloud)[i] = invalid;
114  }
115 
116  // ... otherwise, point is foreground => don't invalidate
117  }
118 
119  sensor_msgs::PointCloud2::Ptr msg = boost::make_shared<sensor_msgs::PointCloud2>();
120  pcl::toROSMsg(*cloud, *msg);
121  msg->header = pc->header;
122  pub.publish(msg);
123 
124  sensor_msgs::PointCloud2::Ptr msg_bg = boost::make_shared<sensor_msgs::PointCloud2>();
125  pcl::toROSMsg(*cloud_bg_, *msg_bg);
126  msg_bg->header = pc->header;
127  pub_bg.publish(msg_bg);
128 }
129 
130 int main(int argc, char **argv)
131 {
132  ros::init(argc, argv, "sick_ldmrs_remove_background");
133  ros::NodeHandle nh;
134  ros::NodeHandle private_nh("~");
135 
136  // min_dist_ratio: a point is filtered out if the distance between it and its
137  // reference point is less than 5% of the distance between the sensor and the
138  // reference point.
139  min_dist_ratio_ = private_nh.param("min_dist_ratio", 0.05);
140 
141  ros::Subscriber sub = nh.subscribe("cloud", 10, callback);
142  pub = nh.advertise<sensor_msgs::PointCloud2>("foreground", 10);
143  pub_bg = nh.advertise<sensor_msgs::PointCloud2>("background", 10);
144 
145  ros::spin();
146 
147  return 0;
148 }
msg
double min_dist_ratio_
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub
void callback(const sensor_msgs::PointCloud2::ConstPtr &pc)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
pcl::PointCloud< PointT > PointCloudT
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
sick_ldmrs_msgs::SICK_LDMRS_Point PointT
int main(int argc, char **argv)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_ERROR_THROTTLE(rate,...)
ros::Publisher pub_bg
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
PointCloudT::Ptr cloud_bg_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)


sick_ldmrs_tools
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Sun Oct 25 2020 03:33:58