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 #include <pcl/common/point_tests.h>
43 
45 typedef pcl::PointCloud<PointT> PointCloudT;
46 
49 
51 
52 PointCloudT::Ptr cloud_bg_;
53 
54 void callback(const sensor_msgs::PointCloud2::ConstPtr& pc)
55 {
56  PointCloudT::Ptr cloud = pcl::make_shared<PointCloudT>();
57  pcl::fromROSMsg(*pc, *cloud);
58 
59  if (!cloud->isOrganized())
60  {
61  ROS_ERROR_THROTTLE(15.0, "Input point cloud is not organized!");
62  return;
63  }
64 
65  if (cloud_bg_ && (cloud->width != cloud_bg_->width || cloud->height != cloud_bg_->height))
66  {
67  ROS_INFO("Dimensions of input cloud different from stored background, resetting background.");
68  cloud_bg_.reset();
69  }
70 
71  if (!cloud_bg_)
72  {
73  cloud_bg_ = cloud;
74  return;
75  }
76 
77  PointT invalid;
78  invalid.x = invalid.y = invalid.z = std::numeric_limits<float>::quiet_NaN();
79 // PointCloudT::Ptr cloud_out = pcl::make_shared<PointCloudT>(width, height, invalid);
80 // cloud_out->is_dense = false;
81 
82  for (size_t i = 0; i < cloud->size(); i++)
83  {
84  const PointT &p_in = cloud->points[i];
85  const PointT &p_bg = cloud_bg_->points[i];
86 
87  // if input point invalid -> output invalid
88  if (!pcl::isFinite<PointT>(p_in))
89  {
90  continue;
91  }
92 
93  // if background invalid (and input valid) -> output valid
94  if (!pcl::isFinite<PointT>(p_bg))
95  {
96  (*cloud_bg_)[i] = p_in; // store new background point
97  continue;
98  }
99 
100  // compare ratio between background and input point to threshold
101  float dist_in = p_in.getVector3fMap().norm();
102  float dist_bg = p_bg.getVector3fMap().norm();
103  float diff = dist_bg - dist_in;
104 
105  if (diff < 0)
106  {
107  // point is further away than previous background
108  (*cloud_bg_)[i] = p_in;
109  (*cloud)[i] = invalid;
110  }
111  else if (diff / dist_bg < min_dist_ratio_)
112  {
113  // point is too close to background
114  (*cloud)[i] = invalid;
115  }
116 
117  // ... otherwise, point is foreground => don't invalidate
118  }
119 
120  sensor_msgs::PointCloud2::Ptr msg = boost::make_shared<sensor_msgs::PointCloud2>();
121  pcl::toROSMsg(*cloud, *msg);
122  msg->header = pc->header;
123  pub.publish(msg);
124 
125  sensor_msgs::PointCloud2::Ptr msg_bg = boost::make_shared<sensor_msgs::PointCloud2>();
126  pcl::toROSMsg(*cloud_bg_, *msg_bg);
127  msg_bg->header = pc->header;
128  pub_bg.publish(msg_bg);
129 }
130 
131 int main(int argc, char **argv)
132 {
133  ros::init(argc, argv, "sick_ldmrs_remove_background");
134  ros::NodeHandle nh;
135  ros::NodeHandle private_nh("~");
136 
137  // min_dist_ratio: a point is filtered out if the distance between it and its
138  // reference point is less than 5% of the distance between the sensor and the
139  // reference point.
140  min_dist_ratio_ = private_nh.param("min_dist_ratio", 0.05);
141 
142  ros::Subscriber sub = nh.subscribe("cloud", 10, callback);
143  pub = nh.advertise<sensor_msgs::PointCloud2>("foreground", 10);
144  pub_bg = nh.advertise<sensor_msgs::PointCloud2>("background", 10);
145 
146  ros::spin();
147 
148  return 0;
149 }
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
msg
msg
ros::Publisher
sick_ldmrs_point_type.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
cloud_bg_
PointCloudT::Ptr cloud_bg_
Definition: sick_ldmrs_remove_background.cpp:52
sick_ldmrs_msgs::SICK_LDMRS_Point
pub
ros::Publisher pub
Definition: sick_ldmrs_remove_background.cpp:47
main
int main(int argc, char **argv)
Definition: sick_ldmrs_remove_background.cpp:131
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
PointT
sick_ldmrs_msgs::SICK_LDMRS_Point PointT
Definition: sick_ldmrs_remove_background.cpp:44
callback
void callback(const sensor_msgs::PointCloud2::ConstPtr &pc)
Definition: sick_ldmrs_remove_background.cpp:54
PointCloudT
pcl::PointCloud< PointT > PointCloudT
Definition: sick_ldmrs_remove_background.cpp:45
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
min_dist_ratio_
double min_dist_ratio_
Definition: sick_ldmrs_remove_background.cpp:50
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
ros::spin
ROSCPP_DECL void spin()
pub_bg
ros::Publisher pub_bg
Definition: sick_ldmrs_remove_background.cpp:48
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle
ros::Subscriber
pcl_conversions.h


sick_ldmrs_tools
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Tue Oct 25 2022 02:14:21