point_cloud_assembler.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2019, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
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  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
30 #include <nodelet/nodelet.h>
31 
32 #include <pcl/point_cloud.h>
33 #include <pcl/point_types.h>
35 #include <pcl/io/pcd_io.h>
36 #include <pcl/filters/voxel_grid.h>
37 #include <pcl/filters/radius_outlier_removal.h>
38 
39 #include <pcl_ros/transforms.h>
40 
41 #include <tf/transform_listener.h>
42 
43 #include <nav_msgs/Odometry.h>
44 #include <sensor_msgs/PointCloud2.h>
45 
48 
50 #include <rtabmap_ros/OdomInfo.h>
51 #include <rtabmap/core/util3d.h>
53 
54 namespace rtabmap_ros
55 {
56 
66 {
67 public:
69  warningThread_(0),
71  exactSync_(0),
72  exactInfoSync_(0),
73  maxClouds_(0),
74  assemblingTime_(0),
75  skipClouds_(0),
76  cloudsSkipped_(0),
79  rangeMin_(0),
80  rangeMax_(0),
81  voxelSize_(0),
82  noiseRadius_(0),
84  fixedFrameId_("odom"),
85  frameId_("")
86  {}
87 
89  {
90  delete exactSync_;
91  delete exactInfoSync_;
92 
93  if(warningThread_)
94  {
95  callbackCalled_=true;
96  warningThread_->join();
97  delete warningThread_;
98  }
99  }
100 
101 private:
102  virtual void onInit()
103  {
106 
107  int queueSize = 5;
108  bool subscribeOdomInfo = false;
109 
110  pnh.param("queue_size", queueSize, queueSize);
111  pnh.param("fixed_frame_id", fixedFrameId_, fixedFrameId_);
112  pnh.param("frame_id", frameId_, frameId_);
113  pnh.param("max_clouds", maxClouds_, maxClouds_);
114  pnh.param("assembling_time", assemblingTime_, assemblingTime_);
115  pnh.param("skip_clouds", skipClouds_, skipClouds_);
116  pnh.param("circular_buffer", circularBuffer_, circularBuffer_);
117  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
118  pnh.param("range_min", rangeMin_, rangeMin_);
119  pnh.param("range_max", rangeMax_, rangeMax_);
120  pnh.param("voxel_size", voxelSize_, voxelSize_);
121  pnh.param("noise_radius", noiseRadius_, noiseRadius_);
122  pnh.param("noise_min_neighbors", noiseMinNeighbors_, noiseMinNeighbors_);
123  pnh.param("subscribe_odom_info", subscribeOdomInfo, subscribeOdomInfo);
125 
126  ROS_INFO("%s: queue_size=%d", getName().c_str(), queueSize);
127  ROS_INFO("%s: fixed_frame_id=%s", getName().c_str(), fixedFrameId_.c_str());
128  ROS_INFO("%s: frame_id=%s", getName().c_str(), frameId_.c_str());
129  ROS_INFO("%s: max_clouds=%d", getName().c_str(), maxClouds_);
130  ROS_INFO("%s: assembling_time=%fs", getName().c_str(), assemblingTime_);
131  ROS_INFO("%s: skip_clouds=%d", getName().c_str(), skipClouds_);
132  ROS_INFO("%s: circular_buffer=%s", getName().c_str(), circularBuffer_?"true":"false");
133  ROS_INFO("%s: wait_for_transform_duration=%f", getName().c_str(), waitForTransformDuration_);
134  ROS_INFO("%s: range_min=%f", getName().c_str(), rangeMin_);
135  ROS_INFO("%s: range_max=%f", getName().c_str(), rangeMax_);
136  ROS_INFO("%s: voxel_size=%fm", getName().c_str(), voxelSize_);
137  ROS_INFO("%s: noise_radius=%fm", getName().c_str(), noiseRadius_);
138  ROS_INFO("%s: noise_min_neighbors=%d", getName().c_str(), noiseMinNeighbors_);
139 
141 
142  std::string subscribedTopicsMsg;
143  if(!fixedFrameId_.empty())
144  {
145  cloudSub_ = nh.subscribe("cloud", queueSize, &PointCloudAssembler::callbackCloud, this);
146  subscribedTopicsMsg = uFormat("\n%s subscribed to %s",
147  getName().c_str(),
148  cloudSub_.getTopic().c_str());
149  }
150  else if(subscribeOdomInfo)
151  {
152  syncCloudSub_.subscribe(nh, "cloud", 1);
153  syncOdomSub_.subscribe(nh, "odom", 1);
154  syncOdomInfoSub_.subscribe(nh, "odom_info", 1);
156  exactInfoSync_->registerCallback(boost::bind(&rtabmap_ros::PointCloudAssembler::callbackCloudOdomInfo, this, _1, _2, _3));
157  subscribedTopicsMsg = uFormat("\n%s subscribed to (exact sync):\n %s,\n %s",
158  getName().c_str(),
159  syncCloudSub_.getTopic().c_str(),
160  syncOdomSub_.getTopic().c_str(),
161  syncOdomInfoSub_.getTopic().c_str());
162 
163  warningThread_ = new boost::thread(boost::bind(&PointCloudAssembler::warningLoop, this, subscribedTopicsMsg));
164  }
165  else
166  {
167  syncCloudSub_.subscribe(nh, "cloud", 1);
168  syncOdomSub_.subscribe(nh, "odom", 1);
170  exactSync_->registerCallback(boost::bind(&rtabmap_ros::PointCloudAssembler::callbackCloudOdom, this, _1, _2));
171  subscribedTopicsMsg = uFormat("\n%s subscribed to (exact sync):\n %s,\n %s",
172  getName().c_str(),
173  syncCloudSub_.getTopic().c_str(),
174  syncOdomSub_.getTopic().c_str());
175 
176  warningThread_ = new boost::thread(boost::bind(&PointCloudAssembler::warningLoop, this, subscribedTopicsMsg));
177  }
178 
179  cloudPub_ = nh.advertise<sensor_msgs::PointCloud2>("assembled_cloud", 1);
180 
181  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
182  }
183 
185  const sensor_msgs::PointCloud2ConstPtr & cloudMsg,
186  const nav_msgs::OdometryConstPtr & odomMsg)
187  {
188  callbackCalled_ = true;
189  rtabmap::Transform odom = rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose);
190  if(!odom.isNull())
191  {
192  fixedFrameId_ = odomMsg->header.frame_id;
193  callbackCloud(cloudMsg);
194  }
195  else
196  {
197  NODELET_WARN("Reseting point cloud assembler as null odometry has been received.");
198  clouds_.clear();
199  }
200  }
201 
203  const sensor_msgs::PointCloud2ConstPtr & cloudMsg,
204  const nav_msgs::OdometryConstPtr & odomMsg,
205  const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg)
206  {
207  callbackCalled_ = true;
208  rtabmap::Transform odom = rtabmap_ros::transformFromPoseMsg(odomMsg->pose.pose);
209  if(!odom.isNull())
210  {
211  if(odomInfoMsg->keyFrameAdded)
212  {
213  fixedFrameId_ = odomMsg->header.frame_id;
214  callbackCloud(cloudMsg);
215  }
216  else
217  {
218  NODELET_INFO("Skipping non keyframe...");
219  }
220  }
221  else
222  {
223  NODELET_WARN("Reseting point cloud assembler as null odometry has been received.");
224  clouds_.clear();
225  }
226  }
227 
228  void callbackCloud(const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
229  {
231  {
232  if(skipClouds_<=0 || cloudsSkipped_ >= skipClouds_)
233  {
234  cloudsSkipped_ = 0;
235 
237  fixedFrameId_, //fromFrame
238  cloudMsg->header.frame_id, //toFrame
239  cloudMsg->header.stamp,
240  tfListener_,
242 
243  if(t.isNull())
244  {
245  ROS_ERROR("Cloud not transform all clouds! Resetting...");
246  clouds_.clear();
247  return;
248  }
249 
250  pcl::PCLPointCloud2::Ptr newCloud(new pcl::PCLPointCloud2);
251  if(rangeMin_ > 0.0 || rangeMax_ > 0.0 || voxelSize_ > 0.0f)
252  {
253  pcl_conversions::toPCL(*cloudMsg, *newCloud);
256 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
257  std::uint64_t stamp = newCloud->header.stamp;
258 #else
259  pcl::uint64_t stamp = newCloud->header.stamp;
260 #endif
261  newCloud = rtabmap::util3d::laserScanToPointCloud2(scan, t);
262  newCloud->header.stamp = stamp;
263  }
264  else
265  {
266  sensor_msgs::PointCloud2 output;
267  pcl_ros::transformPointCloud(t.toEigen4f(), *cloudMsg, output);
268  pcl_conversions::toPCL(output, *newCloud);
269  }
270 
271  clouds_.push_back(newCloud);
272 
273 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
274  bool reachedMaxSize =
275  ((int)clouds_.size() >= maxClouds_ && maxClouds_ > 0)
276  ||
277  ((*newCloud).header.stamp >= clouds_.front()->header.stamp + static_cast<std::uint64_t>(assemblingTime_*1000000.0) && assemblingTime_ > 0.0);
278 #else
279  bool reachedMaxSize =
280  ((int)clouds_.size() >= maxClouds_ && maxClouds_ > 0)
281  ||
282  ((*newCloud).header.stamp >= clouds_.front()->header.stamp + static_cast<pcl::uint64_t>(assemblingTime_*1000000.0) && assemblingTime_ > 0.0);
283 #endif
284 
285  if( circularBuffer_ || reachedMaxSize )
286  {
287  pcl::PCLPointCloud2Ptr assembled(new pcl::PCLPointCloud2);
288  for(std::list<pcl::PCLPointCloud2::Ptr>::iterator iter=clouds_.begin(); iter!=clouds_.end(); ++iter)
289  {
290  if(assembled->data.empty())
291  {
292  *assembled = *(*iter);
293  }
294  else
295  {
296  pcl::PCLPointCloud2Ptr assembledTmp(new pcl::PCLPointCloud2);
297 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
298  pcl::concatenate(*assembled, *(*iter), *assembledTmp);
299 #else
300  pcl::concatenatePointCloud(*assembled, *(*iter), *assembledTmp);
301 #endif
302  assembled = assembledTmp;
303  }
304  }
305 
306  sensor_msgs::PointCloud2 rosCloud;
307  if(voxelSize_>0.0)
308  {
309  pcl::VoxelGrid<pcl::PCLPointCloud2> filter;
310  filter.setLeafSize(voxelSize_, voxelSize_, voxelSize_);
311  filter.setInputCloud(assembled);
312  pcl::PCLPointCloud2Ptr output(new pcl::PCLPointCloud2);
313  filter.filter(*output);
314  assembled = output;
315  }
316  if(noiseRadius_>0.0 && noiseMinNeighbors_>0)
317  {
318  pcl::RadiusOutlierRemoval<pcl::PCLPointCloud2> filter;
319  filter.setRadiusSearch(noiseRadius_);
320  filter.setMinNeighborsInRadius(noiseMinNeighbors_);
321  filter.setInputCloud(assembled);
322  pcl::PCLPointCloud2Ptr output(new pcl::PCLPointCloud2);
323  filter.filter(*output);
324  assembled = output;
325  }
326 
327  pcl_conversions::moveFromPCL(*assembled, rosCloud);
328  if(!frameId_.empty())
329  {
330  // transform in target frame_id instead of sensor frame
332  fixedFrameId_, //fromFrame
333  frameId_, //toFrame
334  cloudMsg->header.stamp,
335  tfListener_,
337  if(t.isNull())
338  {
339  ROS_ERROR("Cloud not transform back assembled clouds in target frame \"%s\"! Resetting...", frameId_.c_str());
340  clouds_.clear();
341  return;
342  }
343  }
344  pcl_ros::transformPointCloud(t.toEigen4f().inverse(), rosCloud, rosCloud);
345 
346  rosCloud.header = cloudMsg->header;
347  if(!frameId_.empty())
348  {
349  rosCloud.header.frame_id = frameId_;
350  }
351  cloudPub_.publish(rosCloud);
352  if(circularBuffer_)
353  {
354  if(reachedMaxSize)
355  {
356  clouds_.pop_front();
357  }
358  }
359  else
360  {
361  clouds_.clear();
362  }
363  }
364  }
365  else
366  {
367  ++cloudsSkipped_;
368  }
369  }
370  }
371 
372  void warningLoop(const std::string & subscribedTopicsMsg)
373  {
374  ros::Duration r(5.0);
375  while(!callbackCalled_)
376  {
377  r.sleep();
378  if(!callbackCalled_)
379  {
380  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
381  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
382  "header are set. %s",
383  getName().c_str(),
384  subscribedTopicsMsg.c_str());
385  }
386  }
387  }
388 
389 private:
390  boost::thread * warningThread_;
392 
395 
403 
410  double rangeMin_;
411  double rangeMax_;
412  double voxelSize_;
413  double noiseRadius_;
415  std::string fixedFrameId_;
416  std::string frameId_;
418 
419  std::list<pcl::PCLPointCloud2::Ptr> clouds_;
420 };
421 
423 }
424 
message_filters::Synchronizer< syncInfoPolicy > * exactInfoSync_
std::string getTopic() const
std::string uFormat(const char *fmt,...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
message_filters::Subscriber< nav_msgs::Odometry > syncOdomSub_
void callbackCloud(const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
bool sleep() const
pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan &laserScan, const Transform &transform=Transform())
const std::string & getName() const
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
#define ROS_WARN(...)
geometry_msgs::TransformStamped t
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
ros::NodeHandle & getPrivateNodeHandle() const
std::list< pcl::PCLPointCloud2::Ptr > clouds_
void callbackCloudOdom(const sensor_msgs::PointCloud2ConstPtr &cloudMsg, const nav_msgs::OdometryConstPtr &odomMsg)
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
bool isNull() const
void warningLoop(const std::string &subscribedTopicsMsg)
#define ROS_INFO(...)
detail::uint64 uint64_t
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string getTopic() const
message_filters::Subscriber< sensor_msgs::PointCloud2 > syncCloudSub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, nav_msgs::Odometry, rtabmap_ros::OdomInfo > syncInfoPolicy
ros::NodeHandle & getNodeHandle() const
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, nav_msgs::Odometry > syncPolicy
bool concatenatePointCloud(const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out)
#define false
message_filters::Subscriber< rtabmap_ros::OdomInfo > syncOdomInfoSub_
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
Eigen::Matrix4f toEigen4f() const
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
void callbackCloudOdomInfo(const sensor_msgs::PointCloud2ConstPtr &cloudMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
message_filters::Synchronizer< syncPolicy > * exactSync_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
#define ROS_ASSERT(cond)
r
#define ROS_ERROR(...)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true, bool is2D=false, const Transform &transform=Transform())


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19