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>
46 
49 
51 #include <rtabmap_msgs/OdomInfo.h>
52 #include <rtabmap/core/util3d.h>
54 #include <rtabmap/core/Version.h>
55 
56 namespace rtabmap_util
57 {
58 
68 {
69 public:
71  warningThread_(0),
73  exactSync_(0),
74  exactInfoSync_(0),
75  maxClouds_(0),
76  assemblingTime_(0),
77  skipClouds_(0),
78  cloudsSkipped_(0),
80  linearUpdate_(0),
81  angularUpdate_(0),
83  rangeMin_(0),
84  rangeMax_(0),
85  voxelSize_(0),
86  noiseRadius_(0),
88  removeZ_(false),
89  fixedFrameId_("odom"),
90  frameId_("")
91  {}
92 
94  {
95  delete exactSync_;
96  delete exactInfoSync_;
97 
98  if(warningThread_)
99  {
100  callbackCalled_=true;
101  warningThread_->join();
102  delete warningThread_;
103  }
104  }
105 
106 private:
107  virtual void onInit()
108  {
111 
112  int queueSize = 1;
113  int syncQueueSize = 5;
114  bool subscribeOdomInfo = false;
115 
116  pnh.param("topic_queue_size", queueSize, queueSize);
117  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
118  {
119  pnh.param("queue_size", syncQueueSize, syncQueueSize);
120  ROS_WARN("Parameter \"queue_size\" has been renamed "
121  "to \"sync_queue_size\" and will be removed "
122  "in future versions! The value (%d) is copied to "
123  "\"sync_queue_size\".", syncQueueSize);
124  }
125  else
126  {
127  pnh.param("sync_queue_size", syncQueueSize, syncQueueSize);
128  }
129  pnh.param("fixed_frame_id", fixedFrameId_, fixedFrameId_);
130  pnh.param("frame_id", frameId_, frameId_);
131  pnh.param("max_clouds", maxClouds_, maxClouds_);
132  pnh.param("assembling_time", assemblingTime_, assemblingTime_);
133  pnh.param("skip_clouds", skipClouds_, skipClouds_);
134  pnh.param("circular_buffer", circularBuffer_, circularBuffer_);
135  pnh.param("linear_update", linearUpdate_, linearUpdate_);
136  pnh.param("angular_update", angularUpdate_, angularUpdate_);
137  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
138  pnh.param("range_min", rangeMin_, rangeMin_);
139  pnh.param("range_max", rangeMax_, rangeMax_);
140  pnh.param("voxel_size", voxelSize_, voxelSize_);
141  pnh.param("noise_radius", noiseRadius_, noiseRadius_);
142  pnh.param("noise_min_neighbors", noiseMinNeighbors_, noiseMinNeighbors_);
143  pnh.param("remove_z", removeZ_, removeZ_);
144  pnh.param("subscribe_odom_info", subscribeOdomInfo, subscribeOdomInfo);
146 
147  ROS_INFO("%s: topic_queue_size=%d", getName().c_str(), queueSize);
148  ROS_INFO("%s: sync_queue_size=%d", getName().c_str(), syncQueueSize);
149  ROS_INFO("%s: fixed_frame_id=%s", getName().c_str(), fixedFrameId_.c_str());
150  ROS_INFO("%s: frame_id=%s", getName().c_str(), frameId_.c_str());
151  ROS_INFO("%s: max_clouds=%d", getName().c_str(), maxClouds_);
152  ROS_INFO("%s: assembling_time=%fs", getName().c_str(), assemblingTime_);
153  ROS_INFO("%s: skip_clouds=%d", getName().c_str(), skipClouds_);
154  ROS_INFO("%s: circular_buffer=%s", getName().c_str(), circularBuffer_?"true":"false");
155  ROS_INFO("%s: linear_update=%f m", getName().c_str(), linearUpdate_);
156  ROS_INFO("%s: angular_update=%f rad", getName().c_str(), angularUpdate_);
157  ROS_INFO("%s: wait_for_transform_duration=%f", getName().c_str(), waitForTransformDuration_);
158  ROS_INFO("%s: range_min=%f", getName().c_str(), rangeMin_);
159  ROS_INFO("%s: range_max=%f", getName().c_str(), rangeMax_);
160  ROS_INFO("%s: voxel_size=%fm", getName().c_str(), voxelSize_);
161  ROS_INFO("%s: noise_radius=%fm", getName().c_str(), noiseRadius_);
162  ROS_INFO("%s: noise_min_neighbors=%d", getName().c_str(), noiseMinNeighbors_);
163  ROS_INFO("%s: remove_z=%s", getName().c_str(), removeZ_?"true":"false");
164 
165  if(maxClouds_==0 && assemblingTime_ ==0.0)
166  {
167  ROS_ERROR("point_cloud_assembler: max_cloud or assembling_time parameters should be set!");
168  exit(-1);
169  }
170 
172 
173  std::string subscribedTopicsMsg;
174  if(!fixedFrameId_.empty())
175  {
176  cloudSub_ = nh.subscribe("cloud", queueSize, &PointCloudAssembler::callbackCloud, this);
177  subscribedTopicsMsg = uFormat("\n%s subscribed to %s",
178  getName().c_str(),
179  cloudSub_.getTopic().c_str());
180  }
181  else if(subscribeOdomInfo)
182  {
183  syncCloudSub_.subscribe(nh, "cloud", queueSize);
184  syncOdomSub_.subscribe(nh, "odom", queueSize);
185  syncOdomInfoSub_.subscribe(nh, "odom_info", queueSize);
187  exactInfoSync_->registerCallback(boost::bind(&rtabmap_util::PointCloudAssembler::callbackCloudOdomInfo, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
188  subscribedTopicsMsg = uFormat("\n%s subscribed to (exact sync):\n %s,\n %s",
189  getName().c_str(),
190  syncCloudSub_.getTopic().c_str(),
191  syncOdomSub_.getTopic().c_str(),
192  syncOdomInfoSub_.getTopic().c_str());
193 
194  warningThread_ = new boost::thread(boost::bind(&PointCloudAssembler::warningLoop, this, subscribedTopicsMsg));
195  }
196  else
197  {
198  syncCloudSub_.subscribe(nh, "cloud", queueSize);
199  syncOdomSub_.subscribe(nh, "odom", queueSize);
201  exactSync_->registerCallback(boost::bind(&rtabmap_util::PointCloudAssembler::callbackCloudOdom, this, boost::placeholders::_1, boost::placeholders::_2));
202  subscribedTopicsMsg = uFormat("\n%s subscribed to (exact sync):\n %s,\n %s",
203  getName().c_str(),
204  syncCloudSub_.getTopic().c_str(),
205  syncOdomSub_.getTopic().c_str());
206 
207  warningThread_ = new boost::thread(boost::bind(&PointCloudAssembler::warningLoop, this, subscribedTopicsMsg));
208  }
209 
210  cloudPub_ = nh.advertise<sensor_msgs::PointCloud2>("assembled_cloud", 1);
211 
212  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
213  }
214 
216  const sensor_msgs::PointCloud2ConstPtr & cloudMsg,
217  const nav_msgs::OdometryConstPtr & odomMsg)
218  {
219  callbackCalled_ = true;
221  if(!odom.isNull())
222  {
223  fixedFrameId_ = odomMsg->header.frame_id;
224  callbackCloud(cloudMsg);
225  }
226  else
227  {
228  NODELET_WARN("Reseting point cloud assembler as null odometry has been received.");
229  clouds_.clear();
230  }
231  }
232 
234  const sensor_msgs::PointCloud2ConstPtr & cloudMsg,
235  const nav_msgs::OdometryConstPtr & odomMsg,
236  const rtabmap_msgs::OdomInfoConstPtr & odomInfoMsg)
237  {
238  callbackCalled_ = true;
240  if(!odom.isNull())
241  {
242  if(odomInfoMsg->keyFrameAdded)
243  {
244  fixedFrameId_ = odomMsg->header.frame_id;
245  callbackCloud(cloudMsg);
246  }
247  else
248  {
249  NODELET_INFO("Skipping non keyframe...");
250  }
251  }
252  else
253  {
254  NODELET_WARN("Reseting point cloud assembler as null odometry has been received.");
255  clouds_.clear();
256  }
257  }
258 
259  sensor_msgs::PointCloud2 removeField(const sensor_msgs::PointCloud2 & input, const std::string & field)
260  {
261  sensor_msgs::PointCloud2 output;
262  int offset = 0;
263  std::vector<int> inputFieldIndex;
264  for(size_t i=0; i<input.fields.size(); ++i)
265  {
266  if(input.fields[i].name.compare(field) == 0)
267  {
268  continue;
269  }
270  else
271  {
272  sensor_msgs::PointField outputField = input.fields[i];
273  outputField.offset = offset;
274  offset += outputField.count * sizeOfPointField(outputField.datatype);
275  output.fields.push_back(outputField);
276  inputFieldIndex.push_back(i);
277  }
278  }
279  output.header = input.header;
280  output.height = input.height;
281  output.width = input.width;
282  output.is_bigendian = input.is_bigendian;
283  output.is_dense = input.is_dense;
284  output.point_step = offset;
285  output.row_step = output.width * output.point_step;
286  output.data.resize(output.height*output.row_step);
287  int total = output.height*output.width;
288  for(int i=0; i<total; ++i)
289  {
290  // for each point, copy fields
291  int oi = i*output.point_step;
292  int pi = i*input.point_step;
293  for(size_t j=0;j<output.fields.size(); ++j)
294  {
295  memcpy(&output.data[oi + output.fields[j].offset],
296  &input.data[pi + input.fields[inputFieldIndex[j]].offset],
297  output.fields[j].count * sizeOfPointField(output.fields[j].datatype));
298  }
299  }
300  return output;
301  }
302 
303  void callbackCloud(const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
304  {
305  callbackCalled_ = true;
307  {
308  UASSERT_MSG(cloudMsg->data.size() == cloudMsg->row_step*cloudMsg->height,
309  uFormat("data=%d row_step=%d height=%d", cloudMsg->data.size(), cloudMsg->row_step, cloudMsg->height).c_str());
310 
311  if(skipClouds_<=0 || cloudsSkipped_ >= skipClouds_)
312  {
313  cloudsSkipped_ = 0;
314 
316  fixedFrameId_, //fromFrame
317  cloudMsg->header.frame_id, //toFrame
318  cloudMsg->header.stamp,
319  tfListener_,
321 
322  if(pose.isNull())
323  {
324  ROS_ERROR("Cloud not transform all clouds! Resetting...");
325  clouds_.clear();
326  return;
327  }
328 
329  bool isMoving = true;
331  {
333  float roll, pitch, yaw;
334  delta.getEulerAngles(roll, pitch, yaw);
335  isMoving = fabs(delta.x()) > linearUpdate_ ||
336  fabs(delta.y()) > linearUpdate_ ||
337  fabs(delta.z()) > linearUpdate_ ||
338  (angularUpdate_>0.0f && (
339  fabs(roll) > angularUpdate_ ||
341  fabs(yaw) > angularUpdate_));
342  }
343 
344  pcl::PCLPointCloud2::Ptr newCloud(new pcl::PCLPointCloud2);
345  if(rangeMin_ > 0.0 || rangeMax_ > 0.0 || voxelSize_ > 0.0f)
346  {
347  pcl_conversions::toPCL(*cloudMsg, *newCloud);
350 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
351  std::uint64_t stamp = newCloud->header.stamp;
352 #else
353  pcl::uint64_t stamp = newCloud->header.stamp;
354 #endif
355  newCloud = rtabmap::util3d::laserScanToPointCloud2(scan, pose);
356  newCloud->header.stamp = stamp;
357  }
358  else
359  {
360  sensor_msgs::PointCloud2 output;
361  pcl_ros::transformPointCloud(pose.toEigen4f(), *cloudMsg, output);
362  pcl_conversions::toPCL(output, *newCloud);
363  }
364 
365  if(!newCloud->is_dense)
366  {
367  // remove nans
368  newCloud = rtabmap::util3d::removeNaNFromPointCloud(newCloud);
369  }
370 
371  clouds_.push_back(newCloud);
372 
373 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
374  bool reachedMaxSize =
375  ((int)clouds_.size() >= maxClouds_ && maxClouds_ > 0)
376  ||
377  ((*newCloud).header.stamp >= clouds_.front()->header.stamp + static_cast<std::uint64_t>(assemblingTime_*1000000.0) && assemblingTime_ > 0.0);
378 #else
379  bool reachedMaxSize =
380  ((int)clouds_.size() >= maxClouds_ && maxClouds_ > 0)
381  ||
382  ((*newCloud).header.stamp >= clouds_.front()->header.stamp + static_cast<pcl::uint64_t>(assemblingTime_*1000000.0) && assemblingTime_ > 0.0);
383 #endif
384 
385  if( circularBuffer_ || reachedMaxSize )
386  {
387  pcl::PCLPointCloud2Ptr assembled(new pcl::PCLPointCloud2);
388  for(std::list<pcl::PCLPointCloud2::Ptr>::iterator iter=clouds_.begin(); iter!=clouds_.end(); ++iter)
389  {
390  if(assembled->data.empty())
391  {
392  *assembled = *(*iter);
393  }
394  else
395  {
396  pcl::PCLPointCloud2Ptr assembledTmp(new pcl::PCLPointCloud2);
397 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
398  pcl::concatenate(*assembled, *(*iter), *assembledTmp);
399 #else
400  pcl::concatenatePointCloud(*assembled, *(*iter), *assembledTmp);
401 #endif
402  //Make sure row_step is the sum of both
403  assembledTmp->row_step = assembled->row_step + (*iter)->row_step;
404  assembled = assembledTmp;
405  }
406  }
407 
408  sensor_msgs::PointCloud2 rosCloud;
409  if(voxelSize_>0.0)
410  {
411  // estimate if there would be an overflow
412  int x_idx=-1, y_idx=-1, z_idx=-1;
413  for (std::size_t d = 0; d < assembled->fields.size (); ++d)
414  {
415  if (assembled->fields[d].name.compare("x")==0)
416  x_idx = d;
417  if (assembled->fields[d].name.compare("y")==0)
418  y_idx = d;
419  if (assembled->fields[d].name.compare("z")==0)
420  z_idx = d;
421  }
422  bool overflow = false;
423  if(x_idx>=0 && y_idx>=0 && z_idx>=0) {
424  Eigen::Vector4f min_p, max_p;
425  pcl::getMinMax3D(assembled, x_idx, y_idx, z_idx, min_p, max_p);
426  float inverseVoxelSize = 1.0f/voxelSize_;
427  std::int64_t dx = static_cast<std::int64_t>((max_p[0] - min_p[0]) * inverseVoxelSize)+1;
428  std::int64_t dy = static_cast<std::int64_t>((max_p[1] - min_p[1]) * inverseVoxelSize)+1;
429  std::int64_t dz = static_cast<std::int64_t>((max_p[2] - min_p[2]) * inverseVoxelSize)+1;
430 
431  if ((dx*dy*dz) > static_cast<std::int64_t>(std::numeric_limits<std::int32_t>::max()))
432  {
433  overflow = true;
434  }
435  }
436  if(overflow)
437  {
439  scan = rtabmap::util3d::commonFiltering(scan, 1, 0, 0, voxelSize_);
440 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
441  std::uint64_t stamp = assembled->header.stamp;
442 #else
443  pcl::uint64_t stamp = assembled->header.stamp;
444 #endif
445  assembled = rtabmap::util3d::laserScanToPointCloud2(scan);
446  assembled->header.stamp = stamp;
447  }
448  else
449  {
450  pcl::VoxelGrid<pcl::PCLPointCloud2> filter;
451  filter.setLeafSize(voxelSize_, voxelSize_, voxelSize_);
452  filter.setInputCloud(assembled);
453  pcl::PCLPointCloud2Ptr output(new pcl::PCLPointCloud2);
454  filter.filter(*output);
455  assembled = output;
456  }
457  }
458  if(noiseRadius_>0.0 && noiseMinNeighbors_>0)
459  {
460  pcl::RadiusOutlierRemoval<pcl::PCLPointCloud2> filter;
461  filter.setRadiusSearch(noiseRadius_);
462  filter.setMinNeighborsInRadius(noiseMinNeighbors_);
463  filter.setInputCloud(assembled);
464  pcl::PCLPointCloud2Ptr output(new pcl::PCLPointCloud2);
465  filter.filter(*output);
466  assembled = output;
467  }
468 
469  pcl_conversions::moveFromPCL(*assembled, rosCloud);
470  rtabmap::Transform t = pose;
471  if(!frameId_.empty())
472  {
473  // transform in target frame_id instead of sensor frame
475  fixedFrameId_, //fromFrame
476  frameId_, //toFrame
477  cloudMsg->header.stamp,
478  tfListener_,
480  if(t.isNull())
481  {
482  ROS_ERROR("Cloud not transform back assembled clouds in target frame \"%s\"! Resetting...", frameId_.c_str());
483  clouds_.clear();
484  return;
485  }
486  }
487  pcl_ros::transformPointCloud(t.toEigen4f().inverse(), rosCloud, rosCloud);
488 
489  if(removeZ_)
490  {
491  rosCloud = removeField(rosCloud, "z");
492  }
493 
494  rosCloud.header = cloudMsg->header;
495  if(!frameId_.empty())
496  {
497  rosCloud.header.frame_id = frameId_;
498  }
499  cloudPub_.publish(rosCloud);
500  if(circularBuffer_)
501  {
502  if(!isMoving)
503  {
504  clouds_.pop_back();
505  }
506  else
507  {
508  previousPose_ = pose;
509  if(reachedMaxSize)
510  {
511  clouds_.pop_front();
512  }
513  }
514  }
515  else
516  {
517  clouds_.clear();
519  }
520  }
521  else if(!isMoving)
522  {
523  clouds_.pop_back();
524  }
525  else
526  {
527  previousPose_ = pose;
528  }
529  }
530  else
531  {
532  ++cloudsSkipped_;
533  }
534  }
535  }
536 
537  void warningLoop(const std::string & subscribedTopicsMsg)
538  {
539  ros::Duration r(5.0);
540  while(!callbackCalled_)
541  {
542  r.sleep();
543  if(!callbackCalled_)
544  {
545  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
546  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
547  "header are set. %s",
548  getName().c_str(),
549  subscribedTopicsMsg.c_str());
550  }
551  }
552  }
553 
554 private:
555  boost::thread * warningThread_;
557 
560 
568 
577  double rangeMin_;
578  double rangeMax_;
579  double voxelSize_;
580  double noiseRadius_;
582  bool removeZ_;
583  std::string fixedFrameId_;
584  std::string frameId_;
587 
588  std::list<pcl::PCLPointCloud2::Ptr> clouds_;
589 };
590 
592 }
593 
int
int
rtabmap::Transform::toEigen4f
Eigen::Matrix4f toEigen4f() const
rtabmap_util::PointCloudAssembler::skipClouds_
int skipClouds_
Definition: point_cloud_assembler.cpp:570
rtabmap_util::PointCloudAssembler::syncOdomSub_
message_filters::Subscriber< nav_msgs::Odometry > syncOdomSub_
Definition: point_cloud_assembler.cpp:566
point_cloud2_iterator.h
rtabmap_util::PointCloudAssembler::angularUpdate_
double angularUpdate_
Definition: point_cloud_assembler.cpp:574
rtabmap_util::PointCloudAssembler::linearUpdate_
double linearUpdate_
Definition: point_cloud_assembler.cpp:573
rtabmap::util3d::laserScanToPointCloud2
pcl::PCLPointCloud2::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloud2(const LaserScan &laserScan, const Transform &transform=Transform())
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
rtabmap_util::PointCloudAssembler::callbackCloudOdom
void callbackCloudOdom(const sensor_msgs::PointCloud2ConstPtr &cloudMsg, const nav_msgs::OdometryConstPtr &odomMsg)
Definition: point_cloud_assembler.cpp:215
int64_t
detail::int64 int64_t
rtabmap_util::PointCloudAssembler::callbackCalled_
bool callbackCalled_
Definition: point_cloud_assembler.cpp:556
message_filters::Synchronizer
rtabmap_util::PointCloudAssembler::callbackCloudOdomInfo
void callbackCloudOdomInfo(const sensor_msgs::PointCloud2ConstPtr &cloudMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)
Definition: point_cloud_assembler.cpp:233
rtabmap_util::PointCloudAssembler::PointCloudAssembler
PointCloudAssembler()
Definition: point_cloud_assembler.cpp:70
rtabmap_conversions::getTransform
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
rtabmap_conversions::transformFromPoseMsg
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
rtabmap_util::PointCloudAssembler::callbackCloud
void callbackCloud(const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
Definition: point_cloud_assembler.cpp:303
rtabmap_util::PointCloudAssembler::exactInfoSync_
message_filters::Synchronizer< syncInfoPolicy > * exactInfoSync_
Definition: point_cloud_assembler.cpp:564
rtabmap_util::PointCloudAssembler::noiseRadius_
double noiseRadius_
Definition: point_cloud_assembler.cpp:580
rtabmap_util::PointCloudAssembler::circularBuffer_
bool circularBuffer_
Definition: point_cloud_assembler.cpp:572
uFormat
std::string uFormat(const char *fmt,...)
ros.h
rtabmap_util::PointCloudAssembler::syncCloudSub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > syncCloudSub_
Definition: point_cloud_assembler.cpp:565
rtabmap::util3d::commonFiltering
RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin, float rangeMax, float voxelSize, int normalK, float normalRadius, bool forceGroundNormalsUp)
rtabmap_util::PointCloudAssembler
Definition: point_cloud_assembler.cpp:67
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
ros::Subscriber::getTopic
std::string getTopic() const
NODELET_WARN
#define NODELET_WARN(...)
uint64_t
detail::uint64 uint64_t
rtabmap::Transform::setNull
void setNull()
rtabmap::LaserScan
rtabmap_util::PointCloudAssembler::assemblingTime_
double assemblingTime_
Definition: point_cloud_assembler.cpp:575
f
Vector3 f(-6, 1, 0.5)
rtabmap_util::PointCloudAssembler::tfListener_
tf::TransformListener tfListener_
Definition: point_cloud_assembler.cpp:585
rtabmap_util
Definition: MapsManager.h:49
rtabmap_util::PointCloudAssembler::clouds_
std::list< pcl::PCLPointCloud2::Ptr > clouds_
Definition: point_cloud_assembler.cpp:588
rtabmap::Transform::isNull
bool isNull() const
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
rtabmap_util::PointCloudAssembler::fixedFrameId_
std::string fixedFrameId_
Definition: point_cloud_assembler.cpp:583
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
transforms.h
rtabmap_util::PointCloudAssembler::rangeMax_
double rangeMax_
Definition: point_cloud_assembler.cpp:578
fabs
Real fabs(const Real &a)
message_filters::Subscriber::getTopic
std::string getTopic() const
message_filters::Subscriber< sensor_msgs::PointCloud2 >
rtabmap_util::PointCloudAssembler::warningLoop
void warningLoop(const std::string &subscribedTopicsMsg)
Definition: point_cloud_assembler.cpp:537
rtabmap_util::PointCloudAssembler::~PointCloudAssembler
virtual ~PointCloudAssembler()
Definition: point_cloud_assembler.cpp:93
delta
def delta(g0, g1)
j
std::ptrdiff_t j
rtabmap_util::PointCloudAssembler::warningThread_
boost::thread * warningThread_
Definition: point_cloud_assembler.cpp:555
rtabmap_util::PointCloudAssembler::removeField
sensor_msgs::PointCloud2 removeField(const sensor_msgs::PointCloud2 &input, const std::string &field)
Definition: point_cloud_assembler.cpp:259
pi
GLM_FUNC_DECL genType pi()
subscriber.h
max
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
rtabmap::util3d::laserScanFromPointCloud
LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud< pcl::PointNormal > &cloud, const pcl::IndicesPtr &indices, const Transform &transform=Transform(), bool filterNaNs=true)
pcl::concatenatePointCloud
bool concatenatePointCloud(const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out)
rtabmap_util::PointCloudAssembler::maxClouds_
int maxClouds_
Definition: point_cloud_assembler.cpp:569
rtabmap_util::PointCloudAssembler::waitForTransformDuration_
double waitForTransformDuration_
Definition: point_cloud_assembler.cpp:576
rtabmap::util3d::removeNaNFromPointCloud
pcl::PCLPointCloud2::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(const pcl::PCLPointCloud2::Ptr &cloud)
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
rtabmap_util::PointCloudAssembler::syncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, nav_msgs::Odometry > syncPolicy
Definition: point_cloud_assembler.cpp:561
d
d
ROS_WARN
#define ROS_WARN(...)
rtabmap_util::PointCloudAssembler::syncOdomInfoSub_
message_filters::Subscriber< rtabmap_msgs::OdomInfo > syncOdomInfoSub_
Definition: point_cloud_assembler.cpp:567
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())
rtabmap_util::PointCloudAssembler::previousPose_
rtabmap::Transform previousPose_
Definition: point_cloud_assembler.cpp:586
pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
rtabmap_util::PointCloudAssembler::cloudsSkipped_
int cloudsSkipped_
Definition: point_cloud_assembler.cpp:571
rtabmap::Transform::inverse
Transform inverse() const
offset
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate offset
UASSERT_MSG
#define UASSERT_MSG(condition, msg_str)
util3d_filtering.h
exact_time.h
rtabmap_util::PointCloudAssembler::voxelSize_
double voxelSize_
Definition: point_cloud_assembler.cpp:579
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
transform_listener.h
rtabmap::Transform
pcl_ros::transformPointCloud
void transformPointCloud(const Eigen::Matrix4f &transform, const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out)
rtabmap_util::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
rtabmap_util::PointCloudAssembler::syncInfoPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, nav_msgs::Odometry, rtabmap_msgs::OdomInfo > syncInfoPolicy
Definition: point_cloud_assembler.cpp:562
nodelet::Nodelet
rtabmap_util::PointCloudAssembler::cloudSub_
ros::Subscriber cloudSub_
Definition: point_cloud_assembler.cpp:558
rtabmap_util::PointCloudAssembler::exactSync_
message_filters::Synchronizer< syncPolicy > * exactSync_
Definition: point_cloud_assembler.cpp:563
rtabmap_util::PointCloudAssembler::onInit
virtual void onInit()
Definition: point_cloud_assembler.cpp:107
iter
iterator iter(handle obj)
nodelet.h
c_str
const char * c_str(Args &&...args)
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
tf::TransformListener
nodelet::Nodelet::getName
const std::string & getName() const
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rtabmap_util::PointCloudAssembler::rangeMin_
double rangeMin_
Definition: point_cloud_assembler.cpp:577
rtabmap_util::PointCloudAssembler::removeZ_
bool removeZ_
Definition: point_cloud_assembler.cpp:582
ros::Duration::sleep
bool sleep() const
false
#define false
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
message_filters::sync_policies::ExactTime
t
Point2 t(10, 10)
ROS_INFO
#define ROS_INFO(...)
rtabmap_util::PointCloudAssembler::noiseMinNeighbors_
int noiseMinNeighbors_
Definition: point_cloud_assembler.cpp:581
ROS_ASSERT
#define ROS_ASSERT(cond)
MsgConversion.h
ros::Duration
rtabmap_util::PointCloudAssembler::cloudPub_
ros::Publisher cloudPub_
Definition: point_cloud_assembler.cpp:559
i
int i
util3d.h
roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
pcl_conversions::moveFromPCL
void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
ros::NodeHandle
ros::Subscriber
rtabmap_util::PointCloudAssembler::frameId_
std::string frameId_
Definition: point_cloud_assembler.cpp:584
pcl_conversions.h


rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50