point_cloud_xyzrgb.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, 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 
37 
38 #include <sensor_msgs/PointCloud2.h>
39 #include <sensor_msgs/Image.h>
41 #include <sensor_msgs/CameraInfo.h>
42 
43 #include <stereo_msgs/DisparityImage.h>
44 
47 
50 
54 
55 #include <cv_bridge/cv_bridge.h>
56 #include <opencv2/highgui/highgui.hpp>
57 
58 #include "rtabmap/core/util2d.h"
59 #include "rtabmap/core/util3d.h"
63 #include "rtabmap/utilite/UStl.h"
64 
65 namespace rtabmap_util
66 {
67 
69 {
70 public:
72  maxDepth_(0.0),
73  minDepth_(0.0),
74  voxelSize_(0.0),
75  decimation_(1),
76  noiseFilterRadius_(0.0),
78  normalK_(0),
79  normalRadius_(0.0),
84  exactSyncDepth_(0),
87  {}
88 
90  {
92  delete approxSyncDepth_;
94  delete approxSyncDisparity_;
96  delete approxSyncStereo_;
97  if(exactSyncDepth_)
98  delete exactSyncDepth_;
100  delete exactSyncDisparity_;
101  if(exactSyncStereo_)
102  delete exactSyncStereo_;
103  }
104 
105 private:
106  virtual void onInit()
107  {
110 
111  int queueSize = 1;
112  int syncQueueSize = 10;
113  bool approxSync = true;
114  std::string roiStr;
115  double approxSyncMaxInterval = 0.0;
116  pnh.param("approx_sync", approxSync, approxSync);
117  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
118  pnh.param("topic_queue_size", queueSize, queueSize);
119  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
120  {
121  pnh.param("queue_size", syncQueueSize, syncQueueSize);
122  ROS_WARN("Parameter \"queue_size\" has been renamed "
123  "to \"sync_queue_size\" and will be removed "
124  "in future versions! The value (%d) is copied to "
125  "\"sync_queue_size\".", syncQueueSize);
126  }
127  else
128  {
129  pnh.param("sync_queue_size", syncQueueSize, syncQueueSize);
130  }
131  pnh.param("max_depth", maxDepth_, maxDepth_);
132  pnh.param("min_depth", minDepth_, minDepth_);
133  pnh.param("voxel_size", voxelSize_, voxelSize_);
134  pnh.param("decimation", decimation_, decimation_);
135  pnh.param("noise_filter_radius", noiseFilterRadius_, noiseFilterRadius_);
136  pnh.param("noise_filter_min_neighbors", noiseFilterMinNeighbors_, noiseFilterMinNeighbors_);
137  pnh.param("normal_k", normalK_, normalK_);
138  pnh.param("normal_radius", normalRadius_, normalRadius_);
139  pnh.param("filter_nans", filterNaNs_, filterNaNs_);
140  pnh.param("roi_ratios", roiStr, roiStr);
141 
142  //parse roi (region of interest)
143  roiRatios_.resize(4, 0);
144  if(!roiStr.empty())
145  {
146  std::list<std::string> strValues = uSplit(roiStr, ' ');
147  if(strValues.size() != 4)
148  {
149  ROS_ERROR("The number of values must be 4 (\"roi_ratios\"=\"%s\")", roiStr.c_str());
150  }
151  else
152  {
153  std::vector<float> tmpValues(4);
154  unsigned int i=0;
155  for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
156  {
157  tmpValues[i] = uStr2Float(*jter);
158  ++i;
159  }
160 
161  if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0f-tmpValues[1] &&
162  tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0f-tmpValues[0] &&
163  tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0f-tmpValues[3] &&
164  tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0f-tmpValues[2])
165  {
166  roiRatios_ = tmpValues;
167  }
168  else
169  {
170  ROS_ERROR("The roi ratios are not valid (\"roi_ratios\"=\"%s\")", roiStr.c_str());
171  }
172  }
173  }
174 
175  // StereoBM parameters
178  stereoBMParameters_.insert(rtabmap::ParametersPair(rtabmap::Parameters::kStereoDenseStrategy(), uNumber2Str(rtabmap::Parameters::defaultStereoDenseStrategy())));
179  for(rtabmap::ParametersMap::iterator iter=stereoBMParameters_.begin(); iter!=stereoBMParameters_.end(); ++iter)
180  {
181  std::string vStr;
182  bool vBool;
183  int vInt;
184  double vDouble;
185  if(pnh.getParam(iter->first, vStr))
186  {
187  NODELET_INFO("point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
188  iter->second = vStr;
189  }
190  else if(pnh.getParam(iter->first, vBool))
191  {
192  NODELET_INFO("point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
193  iter->second = uBool2Str(vBool);
194  }
195  else if(pnh.getParam(iter->first, vDouble))
196  {
197  NODELET_INFO("point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble).c_str());
198  iter->second = uNumber2Str(vDouble);
199  }
200  else if(pnh.getParam(iter->first, vInt))
201  {
202  NODELET_INFO("point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
203  iter->second = uNumber2Str(vInt);
204  }
205  }
206 
207  NODELET_INFO("Approximate time sync = %s", approxSync?"true":"false");
208 
209  cloudPub_ = nh.advertise<sensor_msgs::PointCloud2>("cloud", 1);
210 
211  rgbdImageSub_ = nh.subscribe("rgbd_image", 1, &PointCloudXYZRGB::rgbdImageCallback, this);
212 
213  if(approxSync)
214  {
216  if(approxSyncMaxInterval > 0.0)
217  approxSyncDepth_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
218  approxSyncDepth_->registerCallback(boost::bind(&PointCloudXYZRGB::depthCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
219 
221  if(approxSyncMaxInterval > 0.0)
222  approxSyncDisparity_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
223  approxSyncDisparity_->registerCallback(boost::bind(&PointCloudXYZRGB::disparityCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
224 
226  if(approxSyncMaxInterval > 0.0)
227  approxSyncStereo_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
228  approxSyncStereo_->registerCallback(boost::bind(&PointCloudXYZRGB::stereoCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
229  }
230  else
231  {
233  exactSyncDepth_->registerCallback(boost::bind(&PointCloudXYZRGB::depthCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
234 
236  exactSyncDisparity_->registerCallback(boost::bind(&PointCloudXYZRGB::disparityCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
237 
239  exactSyncStereo_->registerCallback(boost::bind(&PointCloudXYZRGB::stereoCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
240  }
241 
242  ros::NodeHandle rgb_nh(nh, "rgb");
243  ros::NodeHandle depth_nh(nh, "depth");
244  ros::NodeHandle rgb_pnh(pnh, "rgb");
245  ros::NodeHandle depth_pnh(pnh, "depth");
246  image_transport::ImageTransport rgb_it(rgb_nh);
247  image_transport::ImageTransport depth_it(depth_nh);
248  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
249  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
250 
251  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image"), queueSize, hintsRgb);
252  imageDepthSub_.subscribe(depth_it, depth_nh.resolveName("image"), queueSize, hintsDepth);
253  cameraInfoSub_.subscribe(rgb_nh, "camera_info", queueSize);
254 
255  ros::NodeHandle left_nh(nh, "left");
256  ros::NodeHandle right_nh(nh, "right");
257  ros::NodeHandle left_pnh(pnh, "left");
258  ros::NodeHandle right_pnh(pnh, "right");
259  image_transport::ImageTransport left_it(left_nh);
260  image_transport::ImageTransport right_it(right_nh);
261  image_transport::TransportHints hintsLeft("raw", ros::TransportHints(), left_pnh);
262  image_transport::TransportHints hintsRight("raw", ros::TransportHints(), right_pnh);
263 
264  imageDisparitySub_.subscribe(nh, "disparity", queueSize);
265 
266  imageLeft_.subscribe(left_it, left_nh.resolveName("image"), queueSize, hintsLeft);
267  imageRight_.subscribe(right_it, right_nh.resolveName("image"), queueSize, hintsRight);
268  cameraInfoLeft_.subscribe(left_nh, "camera_info", queueSize);
269  cameraInfoRight_.subscribe(right_nh, "camera_info", queueSize);
270  }
271 
273  const sensor_msgs::ImageConstPtr& image,
274  const sensor_msgs::ImageConstPtr& imageDepth,
275  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
276  {
277  if(!(image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1) ==0 ||
278  image->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
279  image->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0 ||
280  image->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
281  image->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0 ||
282  image->encoding.compare(sensor_msgs::image_encodings::BGRA8) == 0 ||
283  image->encoding.compare(sensor_msgs::image_encodings::RGBA8) == 0 ||
284  image->encoding.compare(sensor_msgs::image_encodings::BAYER_GRBG8) == 0) ||
285  !(imageDepth->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)==0 ||
286  imageDepth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0 ||
287  imageDepth->encoding.compare(sensor_msgs::image_encodings::MONO16)==0))
288  {
289  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8 and image_depth=32FC1,16UC1,mono16");
290  return;
291  }
292 
294  {
296 
298  if(image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1)==0)
299  {
300  imagePtr = cv_bridge::toCvShare(image);
301  }
302  else if(image->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
303  image->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
304  {
305  imagePtr = cv_bridge::toCvShare(image, "mono8");
306  }
307  else
308  {
309  imagePtr = cv_bridge::toCvShare(image, "bgr8");
310  }
311 
312  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(imageDepth);
313 
315 
316  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
317 
318  cv::Mat rgb = imagePtr->image;
319  cv::Mat depth = imageDepthPtr->image;
320  if( roiRatios_.size() == 4 &&
321  ((roiRatios_[0] > 0.0f && roiRatios_[0] <= 1.0f) ||
322  (roiRatios_[1] > 0.0f && roiRatios_[1] <= 1.0f) ||
323  (roiRatios_[2] > 0.0f && roiRatios_[2] <= 1.0f) ||
324  (roiRatios_[3] > 0.0f && roiRatios_[3] <= 1.0f)))
325  {
326  cv::Rect roiDepth = rtabmap::util2d::computeRoi(depth, roiRatios_);
327  cv::Rect roiRgb = rtabmap::util2d::computeRoi(rgb, roiRatios_);
328  if( roiDepth.width%decimation_==0 &&
329  roiDepth.height%decimation_==0 &&
330  roiRgb.width%decimation_==0 &&
331  roiRgb.height%decimation_==0)
332  {
333  depth = cv::Mat(depth, roiDepth);
334  rgb = cv::Mat(rgb, roiRgb);
335  model = model.roi(roiRgb);
336  }
337  else
338  {
339  NODELET_ERROR("Cannot apply ROI ratios [%f,%f,%f,%f] because resulting "
340  "dimension (depth=%dx%d rgb=%dx%d) cannot be divided exactly "
341  "by decimation parameter (%d). Ignoring ROI ratios...",
342  roiRatios_[0],
343  roiRatios_[1],
344  roiRatios_[2],
345  roiRatios_[3],
346  roiDepth.width,
347  roiDepth.height,
348  roiRgb.width,
349  roiRgb.height,
350  decimation_);
351  }
352  }
353 
354  pcl::IndicesPtr indices(new std::vector<int>);
356  rgb,
357  depth,
358  model,
359  decimation_,
360  maxDepth_,
361  minDepth_,
362  indices.get());
363 
364 
365  processAndPublish(pclCloud, indices, imagePtr->header);
366 
367  NODELET_DEBUG("point_cloud_xyzrgb from RGB-D time = %f s", (ros::WallTime::now() - time).toSec());
368  }
369  }
370 
372  const sensor_msgs::ImageConstPtr& image,
373  const stereo_msgs::DisparityImageConstPtr& imageDisparity,
374  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
375  {
377  if(image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1)==0)
378  {
379  imagePtr = cv_bridge::toCvShare(image);
380  }
381  else if(image->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
382  image->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
383  {
384  imagePtr = cv_bridge::toCvShare(image, "mono8");
385  }
386  else
387  {
388  imagePtr = cv_bridge::toCvShare(image, "bgr8");
389  }
390 
391  if(imageDisparity->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) !=0 &&
392  imageDisparity->image.encoding.compare(sensor_msgs::image_encodings::TYPE_16SC1) !=0)
393  {
394  NODELET_ERROR("Input type must be disparity=32FC1 or 16SC1");
395  return;
396  }
397 
398  cv::Mat disparity;
399  if(imageDisparity->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) == 0)
400  {
401  disparity = cv::Mat(imageDisparity->image.height, imageDisparity->image.width, CV_32FC1, const_cast<uchar*>(imageDisparity->image.data.data()));
402  }
403  else
404  {
405  disparity = cv::Mat(imageDisparity->image.height, imageDisparity->image.width, CV_16SC1, const_cast<uchar*>(imageDisparity->image.data.data()));
406  }
407 
409  {
411 
412  cv::Rect roi = rtabmap::util2d::computeRoi(disparity, roiRatios_);
413 
414  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
416  UASSERT(disparity.cols == leftModel.imageWidth() && disparity.rows == leftModel.imageHeight());
417  UASSERT(imagePtr->image.cols == leftModel.imageWidth() && imagePtr->image.rows == leftModel.imageHeight());
418  rtabmap::StereoCameraModel stereoModel(imageDisparity->f, imageDisparity->f, leftModel.cx()-roiRatios_[0]*double(disparity.cols), leftModel.cy()-roiRatios_[2]*double(disparity.rows), imageDisparity->T);
419  pcl::IndicesPtr indices(new std::vector<int>);
421  cv::Mat(imagePtr->image, roi),
422  cv::Mat(disparity, roi),
423  stereoModel,
424  decimation_,
425  maxDepth_,
426  minDepth_,
427  indices.get());
428 
429  processAndPublish(pclCloud, indices, imageDisparity->header);
430 
431  NODELET_DEBUG("point_cloud_xyzrgb from disparity time = %f s", (ros::WallTime::now() - time).toSec());
432  }
433  }
434 
435  void stereoCallback(const sensor_msgs::ImageConstPtr& imageLeft,
436  const sensor_msgs::ImageConstPtr& imageRight,
437  const sensor_msgs::CameraInfoConstPtr& camInfoLeft,
438  const sensor_msgs::CameraInfoConstPtr& camInfoRight)
439  {
440  if(!(imageLeft->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
441  imageLeft->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0 ||
442  imageLeft->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
443  imageLeft->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0 ||
444  imageLeft->encoding.compare(sensor_msgs::image_encodings::BGRA8) == 0 ||
445  imageLeft->encoding.compare(sensor_msgs::image_encodings::RGBA8) == 0) ||
446  !(imageRight->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
447  imageRight->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0 ||
448  imageRight->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
449  imageRight->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0 ||
450  imageRight->encoding.compare(sensor_msgs::image_encodings::BGRA8) == 0 ||
451  imageRight->encoding.compare(sensor_msgs::image_encodings::RGBA8) == 0))
452  {
453  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8,rgba8,bgra8 (enc=%s)", imageLeft->encoding.c_str());
454  return;
455  }
456 
458  {
460 
461  cv_bridge::CvImageConstPtr ptrLeftImage, ptrRightImage;
462  if(imageLeft->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
463  imageLeft->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
464  {
465  ptrLeftImage = cv_bridge::toCvShare(imageLeft, "mono8");
466  }
467  else
468  {
469  ptrLeftImage = cv_bridge::toCvShare(imageLeft, "bgr8");
470  }
471  ptrRightImage = cv_bridge::toCvShare(imageRight, "mono8");
472 
473  if(roiRatios_[0]!=0.0f || roiRatios_[1]!=0.0f || roiRatios_[2]!=0.0f || roiRatios_[3]!=0.0f)
474  {
475  ROS_WARN("\"roi_ratios\" set but ignored for stereo images.");
476  }
477 
478  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
479  pcl::IndicesPtr indices(new std::vector<int>);
481  ptrLeftImage->image,
482  ptrRightImage->image,
483  rtabmap_conversions::stereoCameraModelFromROS(*camInfoLeft, *camInfoRight),
484  decimation_,
485  maxDepth_,
486  minDepth_,
487  indices.get(),
489 
490  processAndPublish(pclCloud, indices, imageLeft->header);
491 
492  NODELET_DEBUG("point_cloud_xyzrgb from stereo time = %f s", (ros::WallTime::now() - time).toSec());
493  }
494  }
495 
496  void rgbdImageCallback(const rtabmap_msgs::RGBDImageConstPtr & image)
497  {
499  {
501 
503  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
504  pcl::IndicesPtr indices(new std::vector<int>);
505  if(data.isValid())
506  {
508  data,
509  decimation_,
510  maxDepth_,
511  minDepth_,
512  indices.get(),
514  roiRatios_);
515 
516  processAndPublish(pclCloud, indices, image->header);
517  }
518 
519  NODELET_DEBUG("point_cloud_xyzrgb from rgbd_image time = %f s", (ros::WallTime::now() - time).toSec());
520  }
521  }
522 
523  void processAndPublish(pcl::PointCloud<pcl::PointXYZRGB>::Ptr & pclCloud, pcl::IndicesPtr & indices, const std_msgs::Header & header)
524  {
525  if(indices->size() && voxelSize_ > 0.0)
526  {
527  pclCloud = rtabmap::util3d::voxelize(pclCloud, indices, voxelSize_);
528  pclCloud->is_dense = true;
529  }
530 
531  // Do radius filtering after voxel filtering ( a lot faster)
532  if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && noiseFilterRadius_ > 0.0 && noiseFilterMinNeighbors_ > 0)
533  {
534  if(pclCloud->is_dense)
535  {
537  }
538  else
539  {
541  }
542  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
543  pcl::copyPointCloud(*pclCloud, *indices, *tmp);
544  pclCloud = tmp;
545  }
546 
547  sensor_msgs::PointCloud2 rosCloud;
548  if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && (normalK_ > 0 || normalRadius_ > 0.0f))
549  {
550  //compute normals
551  pcl::PointCloud<pcl::Normal>::Ptr normals = rtabmap::util3d::computeNormals(pclCloud, normalK_, normalRadius_);
552  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr pclCloudNormal(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
553  pcl::concatenateFields(*pclCloud, *normals, *pclCloudNormal);
554  if(filterNaNs_)
555  {
556  pclCloudNormal = rtabmap::util3d::removeNaNNormalsFromPointCloud(pclCloudNormal);
557  }
558  pcl::toROSMsg(*pclCloudNormal, rosCloud);
559  }
560  else
561  {
562  if(filterNaNs_ && !pclCloud->is_dense)
563  {
564  pclCloud = rtabmap::util3d::removeNaNFromPointCloud(pclCloud);
565  }
566  pcl::toROSMsg(*pclCloud, rosCloud);
567  }
568  rosCloud.header.stamp = header.stamp;
569  rosCloud.header.frame_id = header.frame_id;
570 
571  //publish the message
572  cloudPub_.publish(rosCloud);
573  }
574 
575 private:
576 
577  double maxDepth_;
578  double minDepth_;
579  double voxelSize_;
583  int normalK_;
586  std::vector<float> roiRatios_;
588 
590 
592 
596 
598 
603 
606 
609 
612 
615 
618 
621 };
622 
624 }
625 
rtabmap::SensorData
rtabmap_util::PointCloudXYZRGB::MyApproxSyncDisparityPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyApproxSyncDisparityPolicy
Definition: point_cloud_xyzrgb.cpp:607
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
rtabmap_util::PointCloudXYZRGB::normalRadius_
double normalRadius_
Definition: point_cloud_xyzrgb.cpp:584
image_transport::SubscriberFilter
rtabmap::CameraModel::cx
double cx() const
rtabmap::util2d::computeRoi
cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat &image, const std::string &roiRatios)
rtabmap::CameraModel::imageWidth
int imageWidth() const
sensor_msgs::image_encodings::TYPE_8UC1
const std::string TYPE_8UC1
NODELET_ERROR
#define NODELET_ERROR(...)
rtabmap::StereoCameraModel
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
rtabmap_util::PointCloudXYZRGB::minDepth_
double minDepth_
Definition: point_cloud_xyzrgb.cpp:578
image_encodings.h
image_transport::ImageTransport
rtabmap_util::PointCloudXYZRGB::MyExactSyncDisparityPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyExactSyncDisparityPolicy
Definition: point_cloud_xyzrgb.cpp:616
message_filters::Synchronizer
boost::shared_ptr
rtabmap_util::PointCloudXYZRGB::maxDepth_
double maxDepth_
Definition: point_cloud_xyzrgb.cpp:577
uchar
unsigned char uchar
pinhole_camera_model.h
rtabmap_util::PointCloudXYZRGB::roiRatios_
std::vector< float > roiRatios_
Definition: point_cloud_xyzrgb.cpp:586
rtabmap::util3d::removeNaNNormalsFromPointCloud
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
rtabmap_util::PointCloudXYZRGB::filterNaNs_
bool filterNaNs_
Definition: point_cloud_xyzrgb.cpp:585
rtabmap_util::PointCloudXYZRGB::voxelSize_
double voxelSize_
Definition: point_cloud_xyzrgb.cpp:579
rtabmap::util3d::cloudFromStereoImages
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT cloudFromStereoImages(const cv::Mat &imageLeft, const cv::Mat &imageRight, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &parameters=ParametersMap())
rtabmap_util::PointCloudXYZRGB::imageLeft_
image_transport::SubscriberFilter imageLeft_
Definition: point_cloud_xyzrgb.cpp:599
rtabmap::CameraModel::cy
double cy() const
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
rtabmap_util::PointCloudXYZRGB::cloudPub_
ros::Publisher cloudPub_
Definition: point_cloud_xyzrgb.cpp:589
ros.h
rtabmap::CameraModel
rtabmap::util3d::cloudFromDepthRGB
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT cloudFromDepthRGB(const cv::Mat &imageRgb, const cv::Mat &imageDepth, const CameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
rtabmap_util::PointCloudXYZRGB::MyApproxSyncStereoPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncStereoPolicy
Definition: point_cloud_xyzrgb.cpp:610
sensor_msgs::image_encodings::RGBA8
const std::string RGBA8
rtabmap_util::PointCloudXYZRGB::normalK_
int normalK_
Definition: point_cloud_xyzrgb.cpp:583
rtabmap_conversions::cameraModelFromROS
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
ros::TransportHints
UStl.h
rtabmap_util::PointCloudXYZRGB::processAndPublish
void processAndPublish(pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pclCloud, pcl::IndicesPtr &indices, const std_msgs::Header &header)
Definition: point_cloud_xyzrgb.cpp:523
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
rtabmap_util::PointCloudXYZRGB::decimation_
int decimation_
Definition: point_cloud_xyzrgb.cpp:580
rtabmap_util::PointCloudXYZRGB::MyExactSyncDepthPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
Definition: point_cloud_xyzrgb.cpp:613
rtabmap::util3d::radiusFiltering
pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
sensor_msgs::image_encodings::RGB8
const std::string RGB8
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
f
Vector3 f(-6, 1, 0.5)
uNumber2Str
std::string uNumber2Str(double number, int precision, bool fixed)
rtabmap_util
Definition: MapsManager.h:49
rtabmap_util::PointCloudXYZRGB::cameraInfoRight_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
Definition: point_cloud_xyzrgb.cpp:602
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
rtabmap_util::PointCloudXYZRGB::onInit
virtual void onInit()
Definition: point_cloud_xyzrgb.cpp:106
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
stereo_camera_model.h
indices
indices
rtabmap_util::PointCloudXYZRGB::rgbdImageSub_
ros::Subscriber rgbdImageSub_
Definition: point_cloud_xyzrgb.cpp:591
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
message_filters::Subscriber< sensor_msgs::CameraInfo >
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
rtabmap_util::PointCloudXYZRGB::rgbdImageCallback
void rgbdImageCallback(const rtabmap_msgs::RGBDImageConstPtr &image)
Definition: point_cloud_xyzrgb.cpp:496
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
rtabmap::util3d::cloudRGBFromSensorData
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
rtabmap_conversions::stereoCameraModelFromROS
rtabmap::StereoCameraModel stereoCameraModelFromROS(const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity(), const rtabmap::Transform &stereoTransform=rtabmap::Transform())
uBool2Str
std::string uBool2Str(bool boolean)
data
int data[]
message_filters::sync_policies::ApproximateTime
rtabmap_util::PointCloudXYZRGB::MyExactSyncStereoPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncStereoPolicy
Definition: point_cloud_xyzrgb.cpp:619
uInsert
void uInsert(std::map< K, V > &map, const std::map< K, V > &items)
subscriber_filter.h
rtabmap::util3d::voxelize
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT voxelize(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
rtabmap_util::PointCloudXYZRGB::approxSyncDepth_
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
Definition: point_cloud_xyzrgb.cpp:605
rtabmap_util::PointCloudXYZRGB
Definition: point_cloud_xyzrgb.cpp:68
subscriber.h
ros::WallTime::now
static WallTime now()
rtabmap_util::PointCloudXYZRGB::exactSyncDisparity_
message_filters::Synchronizer< MyExactSyncDisparityPolicy > * exactSyncDisparity_
Definition: point_cloud_xyzrgb.cpp:617
rtabmap_util::PointCloudXYZRGB::noiseFilterRadius_
double noiseFilterRadius_
Definition: point_cloud_xyzrgb.cpp:581
rtabmap_util::PointCloudXYZRGB::disparityCallback
void disparityCallback(const sensor_msgs::ImageConstPtr &image, const stereo_msgs::DisparityImageConstPtr &imageDisparity, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
Definition: point_cloud_xyzrgb.cpp:371
rtabmap_util::PointCloudXYZRGB::stereoCallback
void stereoCallback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &camInfoLeft, const sensor_msgs::CameraInfoConstPtr &camInfoRight)
Definition: point_cloud_xyzrgb.cpp:435
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::PointCloudXYZRGB::imageDisparitySub_
message_filters::Subscriber< stereo_msgs::DisparityImage > imageDisparitySub_
Definition: point_cloud_xyzrgb.cpp:597
UASSERT
#define UASSERT(condition)
ROS_WARN
#define ROS_WARN(...)
rtabmap_util::PointCloudXYZRGB::exactSyncDepth_
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
Definition: point_cloud_xyzrgb.cpp:614
rtabmap_util::PointCloudXYZRGB::stereoBMParameters_
rtabmap::ParametersMap stereoBMParameters_
Definition: point_cloud_xyzrgb.cpp:587
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::PointCloudXYZRGB::exactSyncStereo_
message_filters::Synchronizer< MyExactSyncStereoPolicy > * exactSyncStereo_
Definition: point_cloud_xyzrgb.cpp:620
rtabmap_util::PointCloudXYZRGB::MyApproxSyncDepthPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
Definition: point_cloud_xyzrgb.cpp:604
time
#define time
ros::WallTime
model
noiseModel::Diagonal::shared_ptr model
rtabmap_util::PointCloudXYZRGB::imageRight_
image_transport::SubscriberFilter imageRight_
Definition: point_cloud_xyzrgb.cpp:600
rtabmap_util::PointCloudXYZRGB::cameraInfoSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: point_cloud_xyzrgb.cpp:595
image_transport.h
util3d_filtering.h
rtabmap_util::PointCloudXYZRGB::imageSub_
image_transport::SubscriberFilter imageSub_
Definition: point_cloud_xyzrgb.cpp:593
exact_time.h
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
rtabmap_util::PointCloudXYZRGB::PointCloudXYZRGB
PointCloudXYZRGB()
Definition: point_cloud_xyzrgb.cpp:71
rtabmap_util::PointCloudXYZRGB::approxSyncDisparity_
message_filters::Synchronizer< MyApproxSyncDisparityPolicy > * approxSyncDisparity_
Definition: point_cloud_xyzrgb.cpp:608
uSplit
std::list< std::string > uSplit(const std::string &str, char separator=' ')
rtabmap_util::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
nodelet::Nodelet
rtabmap_util::PointCloudXYZRGB::cameraInfoLeft_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
Definition: point_cloud_xyzrgb.cpp:601
sensor_msgs::image_encodings::BGRA8
const std::string BGRA8
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
iter
iterator iter(handle obj)
rtabmap::util3d::cloudFromDisparityRGB
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT cloudFromDisparityRGB(const cv::Mat &imageRgb, const cv::Mat &imageDisparity, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
nodelet.h
sensor_msgs::image_encodings::MONO8
const std::string MONO8
c_str
const char * c_str(Args &&...args)
cv_bridge.h
sensor_msgs::image_encodings::MONO16
const std::string MONO16
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rtabmap::CameraModel::imageHeight
int imageHeight() const
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
rtabmap_util::PointCloudXYZRGB::~PointCloudXYZRGB
virtual ~PointCloudXYZRGB()
Definition: point_cloud_xyzrgb.cpp:89
approximate_time.h
rtabmap_conversions::rgbdImageFromROS
rtabmap::SensorData rgbdImageFromROS(const rtabmap_msgs::RGBDImageConstPtr &image)
sensor_msgs::image_encodings::TYPE_16SC1
const std::string TYPE_16SC1
sensor_msgs::image_encodings::BGR8
const std::string BGR8
sensor_msgs::image_encodings::BAYER_GRBG8
const std::string BAYER_GRBG8
false
#define false
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
rtabmap::util3d::computeNormals
cv::Mat RTABMAP_CORE_EXPORT computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
image_transport::TransportHints
util3d_surface.h
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
message_filters::sync_policies::ExactTime
header
const std::string header
uStr2Float
float uStr2Float(const std::string &str)
UConversion.h
MsgConversion.h
rtabmap_util::PointCloudXYZRGB::depthCallback
void depthCallback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
Definition: point_cloud_xyzrgb.cpp:272
ros::Duration
i
int i
rtabmap_util::PointCloudXYZRGB::imageDepthSub_
image_transport::SubscriberFilter imageDepthSub_
Definition: point_cloud_xyzrgb.cpp:594
util3d.h
ros::NodeHandle
ros::Subscriber
rtabmap_util::PointCloudXYZRGB::approxSyncStereo_
message_filters::Synchronizer< MyApproxSyncStereoPolicy > * approxSyncStereo_
Definition: point_cloud_xyzrgb.cpp:611
NODELET_DEBUG
#define NODELET_DEBUG(...)
util2d.h
rtabmap_util::PointCloudXYZRGB::noiseFilterMinNeighbors_
int noiseFilterMinNeighbors_
Definition: point_cloud_xyzrgb.cpp:582
pcl_conversions.h


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