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_ros
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 = 10;
112  bool approxSync = true;
113  std::string roiStr;
114  double approxSyncMaxInterval = 0.0;
115  pnh.param("approx_sync", approxSync, approxSync);
116  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
117  pnh.param("queue_size", queueSize, queueSize);
118  pnh.param("max_depth", maxDepth_, maxDepth_);
119  pnh.param("min_depth", minDepth_, minDepth_);
120  pnh.param("voxel_size", voxelSize_, voxelSize_);
121  pnh.param("decimation", decimation_, decimation_);
122  pnh.param("noise_filter_radius", noiseFilterRadius_, noiseFilterRadius_);
123  pnh.param("noise_filter_min_neighbors", noiseFilterMinNeighbors_, noiseFilterMinNeighbors_);
124  pnh.param("normal_k", normalK_, normalK_);
125  pnh.param("normal_radius", normalRadius_, normalRadius_);
126  pnh.param("filter_nans", filterNaNs_, filterNaNs_);
127  pnh.param("roi_ratios", roiStr, roiStr);
128 
129  //parse roi (region of interest)
130  roiRatios_.resize(4, 0);
131  if(!roiStr.empty())
132  {
133  std::list<std::string> strValues = uSplit(roiStr, ' ');
134  if(strValues.size() != 4)
135  {
136  ROS_ERROR("The number of values must be 4 (\"roi_ratios\"=\"%s\")", roiStr.c_str());
137  }
138  else
139  {
140  std::vector<float> tmpValues(4);
141  unsigned int i=0;
142  for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
143  {
144  tmpValues[i] = uStr2Float(*jter);
145  ++i;
146  }
147 
148  if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0f-tmpValues[1] &&
149  tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0f-tmpValues[0] &&
150  tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0f-tmpValues[3] &&
151  tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0f-tmpValues[2])
152  {
153  roiRatios_ = tmpValues;
154  }
155  else
156  {
157  ROS_ERROR("The roi ratios are not valid (\"roi_ratios\"=\"%s\")", roiStr.c_str());
158  }
159  }
160  }
161 
162  // StereoBM parameters
164  for(rtabmap::ParametersMap::iterator iter=stereoBMParameters_.begin(); iter!=stereoBMParameters_.end(); ++iter)
165  {
166  std::string vStr;
167  bool vBool;
168  int vInt;
169  double vDouble;
170  if(pnh.getParam(iter->first, vStr))
171  {
172  NODELET_INFO("point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
173  iter->second = vStr;
174  }
175  else if(pnh.getParam(iter->first, vBool))
176  {
177  NODELET_INFO("point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
178  iter->second = uBool2Str(vBool);
179  }
180  else if(pnh.getParam(iter->first, vDouble))
181  {
182  NODELET_INFO("point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble).c_str());
183  iter->second = uNumber2Str(vDouble);
184  }
185  else if(pnh.getParam(iter->first, vInt))
186  {
187  NODELET_INFO("point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
188  iter->second = uNumber2Str(vInt);
189  }
190  }
191 
192  NODELET_INFO("Approximate time sync = %s", approxSync?"true":"false");
193 
194  cloudPub_ = nh.advertise<sensor_msgs::PointCloud2>("cloud", 1);
195 
196  rgbdImageSub_ = nh.subscribe("rgbd_image", 1, &PointCloudXYZRGB::rgbdImageCallback, this);
197 
198  if(approxSync)
199  {
201  if(approxSyncMaxInterval > 0.0)
202  approxSyncDepth_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
203  approxSyncDepth_->registerCallback(boost::bind(&PointCloudXYZRGB::depthCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
204 
206  if(approxSyncMaxInterval > 0.0)
207  approxSyncDisparity_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
208  approxSyncDisparity_->registerCallback(boost::bind(&PointCloudXYZRGB::disparityCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
209 
211  if(approxSyncMaxInterval > 0.0)
212  approxSyncStereo_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
213  approxSyncStereo_->registerCallback(boost::bind(&PointCloudXYZRGB::stereoCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
214  }
215  else
216  {
218  exactSyncDepth_->registerCallback(boost::bind(&PointCloudXYZRGB::depthCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
219 
221  exactSyncDisparity_->registerCallback(boost::bind(&PointCloudXYZRGB::disparityCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
222 
224  exactSyncStereo_->registerCallback(boost::bind(&PointCloudXYZRGB::stereoCallback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
225  }
226 
227  ros::NodeHandle rgb_nh(nh, "rgb");
228  ros::NodeHandle depth_nh(nh, "depth");
229  ros::NodeHandle rgb_pnh(pnh, "rgb");
230  ros::NodeHandle depth_pnh(pnh, "depth");
231  image_transport::ImageTransport rgb_it(rgb_nh);
232  image_transport::ImageTransport depth_it(depth_nh);
233  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
234  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
235 
236  imageSub_.subscribe(rgb_it, rgb_nh.resolveName("image"), 1, hintsRgb);
237  imageDepthSub_.subscribe(depth_it, depth_nh.resolveName("image"), 1, hintsDepth);
238  cameraInfoSub_.subscribe(rgb_nh, "camera_info", 1);
239 
240  ros::NodeHandle left_nh(nh, "left");
241  ros::NodeHandle right_nh(nh, "right");
242  ros::NodeHandle left_pnh(pnh, "left");
243  ros::NodeHandle right_pnh(pnh, "right");
244  image_transport::ImageTransport left_it(left_nh);
245  image_transport::ImageTransport right_it(right_nh);
246  image_transport::TransportHints hintsLeft("raw", ros::TransportHints(), left_pnh);
247  image_transport::TransportHints hintsRight("raw", ros::TransportHints(), right_pnh);
248 
249  imageDisparitySub_.subscribe(nh, "disparity", 1);
250 
251  imageLeft_.subscribe(left_it, left_nh.resolveName("image"), 1, hintsLeft);
252  imageRight_.subscribe(right_it, right_nh.resolveName("image"), 1, hintsRight);
253  cameraInfoLeft_.subscribe(left_nh, "camera_info", 1);
254  cameraInfoRight_.subscribe(right_nh, "camera_info", 1);
255  }
256 
258  const sensor_msgs::ImageConstPtr& image,
259  const sensor_msgs::ImageConstPtr& imageDepth,
260  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
261  {
262  if(!(image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1) ==0 ||
263  image->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
264  image->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0 ||
265  image->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
266  image->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0 ||
267  image->encoding.compare(sensor_msgs::image_encodings::BGRA8) == 0 ||
268  image->encoding.compare(sensor_msgs::image_encodings::RGBA8) == 0 ||
269  image->encoding.compare(sensor_msgs::image_encodings::BAYER_GRBG8) == 0) ||
270  !(imageDepth->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)==0 ||
271  imageDepth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0 ||
272  imageDepth->encoding.compare(sensor_msgs::image_encodings::MONO16)==0))
273  {
274  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8 and image_depth=32FC1,16UC1,mono16");
275  return;
276  }
277 
279  {
281 
283  if(image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1)==0)
284  {
285  imagePtr = cv_bridge::toCvShare(image);
286  }
287  else if(image->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
288  image->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
289  {
290  imagePtr = cv_bridge::toCvShare(image, "mono8");
291  }
292  else
293  {
294  imagePtr = cv_bridge::toCvShare(image, "bgr8");
295  }
296 
297  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(imageDepth);
298 
300 
301  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
302 
303  cv::Mat rgb = imagePtr->image;
304  cv::Mat depth = imageDepthPtr->image;
305  if( roiRatios_.size() == 4 &&
306  ((roiRatios_[0] > 0.0f && roiRatios_[0] <= 1.0f) ||
307  (roiRatios_[1] > 0.0f && roiRatios_[1] <= 1.0f) ||
308  (roiRatios_[2] > 0.0f && roiRatios_[2] <= 1.0f) ||
309  (roiRatios_[3] > 0.0f && roiRatios_[3] <= 1.0f)))
310  {
311  cv::Rect roiDepth = rtabmap::util2d::computeRoi(depth, roiRatios_);
312  cv::Rect roiRgb = rtabmap::util2d::computeRoi(rgb, roiRatios_);
313  if( roiDepth.width%decimation_==0 &&
314  roiDepth.height%decimation_==0 &&
315  roiRgb.width%decimation_==0 &&
316  roiRgb.height%decimation_==0)
317  {
318  depth = cv::Mat(depth, roiDepth);
319  rgb = cv::Mat(rgb, roiRgb);
320  model = model.roi(roiRgb);
321  }
322  else
323  {
324  NODELET_ERROR("Cannot apply ROI ratios [%f,%f,%f,%f] because resulting "
325  "dimension (depth=%dx%d rgb=%dx%d) cannot be divided exactly "
326  "by decimation parameter (%d). Ignoring ROI ratios...",
327  roiRatios_[0],
328  roiRatios_[1],
329  roiRatios_[2],
330  roiRatios_[3],
331  roiDepth.width,
332  roiDepth.height,
333  roiRgb.width,
334  roiRgb.height,
335  decimation_);
336  }
337  }
338 
339  pcl::IndicesPtr indices(new std::vector<int>);
341  rgb,
342  depth,
343  model,
344  decimation_,
345  maxDepth_,
346  minDepth_,
347  indices.get());
348 
349 
350  processAndPublish(pclCloud, indices, imagePtr->header);
351 
352  NODELET_DEBUG("point_cloud_xyzrgb from RGB-D time = %f s", (ros::WallTime::now() - time).toSec());
353  }
354  }
355 
357  const sensor_msgs::ImageConstPtr& image,
358  const stereo_msgs::DisparityImageConstPtr& imageDisparity,
359  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
360  {
362  if(image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1)==0)
363  {
364  imagePtr = cv_bridge::toCvShare(image);
365  }
366  else if(image->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
367  image->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
368  {
369  imagePtr = cv_bridge::toCvShare(image, "mono8");
370  }
371  else
372  {
373  imagePtr = cv_bridge::toCvShare(image, "bgr8");
374  }
375 
376  if(imageDisparity->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) !=0 &&
377  imageDisparity->image.encoding.compare(sensor_msgs::image_encodings::TYPE_16SC1) !=0)
378  {
379  NODELET_ERROR("Input type must be disparity=32FC1 or 16SC1");
380  return;
381  }
382 
383  cv::Mat disparity;
384  if(imageDisparity->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) == 0)
385  {
386  disparity = cv::Mat(imageDisparity->image.height, imageDisparity->image.width, CV_32FC1, const_cast<uchar*>(imageDisparity->image.data.data()));
387  }
388  else
389  {
390  disparity = cv::Mat(imageDisparity->image.height, imageDisparity->image.width, CV_16SC1, const_cast<uchar*>(imageDisparity->image.data.data()));
391  }
392 
394  {
396 
397  cv::Rect roi = rtabmap::util2d::computeRoi(disparity, roiRatios_);
398 
399  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
400  rtabmap::CameraModel leftModel = rtabmap_ros::cameraModelFromROS(*cameraInfo);
401  UASSERT(disparity.cols == leftModel.imageWidth() && disparity.rows == leftModel.imageHeight());
402  UASSERT(imagePtr->image.cols == leftModel.imageWidth() && imagePtr->image.rows == leftModel.imageHeight());
403  rtabmap::StereoCameraModel stereoModel(imageDisparity->f, imageDisparity->f, leftModel.cx()-roiRatios_[0]*double(disparity.cols), leftModel.cy()-roiRatios_[2]*double(disparity.rows), imageDisparity->T);
404  pcl::IndicesPtr indices(new std::vector<int>);
406  cv::Mat(imagePtr->image, roi),
407  cv::Mat(disparity, roi),
408  stereoModel,
409  decimation_,
410  maxDepth_,
411  minDepth_,
412  indices.get());
413 
414  processAndPublish(pclCloud, indices, imageDisparity->header);
415 
416  NODELET_DEBUG("point_cloud_xyzrgb from disparity time = %f s", (ros::WallTime::now() - time).toSec());
417  }
418  }
419 
420  void stereoCallback(const sensor_msgs::ImageConstPtr& imageLeft,
421  const sensor_msgs::ImageConstPtr& imageRight,
422  const sensor_msgs::CameraInfoConstPtr& camInfoLeft,
423  const sensor_msgs::CameraInfoConstPtr& camInfoRight)
424  {
425  if(!(imageLeft->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
426  imageLeft->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0 ||
427  imageLeft->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
428  imageLeft->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0 ||
429  imageLeft->encoding.compare(sensor_msgs::image_encodings::BGRA8) == 0 ||
430  imageLeft->encoding.compare(sensor_msgs::image_encodings::RGBA8) == 0) ||
431  !(imageRight->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
432  imageRight->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0 ||
433  imageRight->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
434  imageRight->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0 ||
435  imageRight->encoding.compare(sensor_msgs::image_encodings::BGRA8) == 0 ||
436  imageRight->encoding.compare(sensor_msgs::image_encodings::RGBA8) == 0))
437  {
438  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8,rgba8,bgra8 (enc=%s)", imageLeft->encoding.c_str());
439  return;
440  }
441 
443  {
445 
446  cv_bridge::CvImageConstPtr ptrLeftImage, ptrRightImage;
447  if(imageLeft->encoding.compare(sensor_msgs::image_encodings::MONO8) == 0 ||
448  imageLeft->encoding.compare(sensor_msgs::image_encodings::MONO16) == 0)
449  {
450  ptrLeftImage = cv_bridge::toCvShare(imageLeft, "mono8");
451  }
452  else
453  {
454  ptrLeftImage = cv_bridge::toCvShare(imageLeft, "bgr8");
455  }
456  ptrRightImage = cv_bridge::toCvShare(imageRight, "mono8");
457 
458  if(roiRatios_[0]!=0.0f || roiRatios_[1]!=0.0f || roiRatios_[2]!=0.0f || roiRatios_[3]!=0.0f)
459  {
460  ROS_WARN("\"roi_ratios\" set but ignored for stereo images.");
461  }
462 
463  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
464  pcl::IndicesPtr indices(new std::vector<int>);
466  ptrLeftImage->image,
467  ptrRightImage->image,
468  rtabmap_ros::stereoCameraModelFromROS(*camInfoLeft, *camInfoRight),
469  decimation_,
470  maxDepth_,
471  minDepth_,
472  indices.get(),
474 
475  processAndPublish(pclCloud, indices, imageLeft->header);
476 
477  NODELET_DEBUG("point_cloud_xyzrgb from stereo time = %f s", (ros::WallTime::now() - time).toSec());
478  }
479  }
480 
481  void rgbdImageCallback(const rtabmap_ros::RGBDImageConstPtr & image)
482  {
484  {
486 
488  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
489  pcl::IndicesPtr indices(new std::vector<int>);
490  if(data.isValid())
491  {
493  data,
494  decimation_,
495  maxDepth_,
496  minDepth_,
497  indices.get(),
499  roiRatios_);
500 
501  processAndPublish(pclCloud, indices, image->header);
502  }
503 
504  NODELET_DEBUG("point_cloud_xyzrgb from rgbd_image time = %f s", (ros::WallTime::now() - time).toSec());
505  }
506  }
507 
508  void processAndPublish(pcl::PointCloud<pcl::PointXYZRGB>::Ptr & pclCloud, pcl::IndicesPtr & indices, const std_msgs::Header & header)
509  {
510  if(indices->size() && voxelSize_ > 0.0)
511  {
512  pclCloud = rtabmap::util3d::voxelize(pclCloud, indices, voxelSize_);
513  pclCloud->is_dense = true;
514  }
515 
516  // Do radius filtering after voxel filtering ( a lot faster)
517  if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && noiseFilterRadius_ > 0.0 && noiseFilterMinNeighbors_ > 0)
518  {
519  if(pclCloud->is_dense)
520  {
522  }
523  else
524  {
526  }
527  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
528  pcl::copyPointCloud(*pclCloud, *indices, *tmp);
529  pclCloud = tmp;
530  }
531 
532  sensor_msgs::PointCloud2 rosCloud;
533  if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && (normalK_ > 0 || normalRadius_ > 0.0f))
534  {
535  //compute normals
536  pcl::PointCloud<pcl::Normal>::Ptr normals = rtabmap::util3d::computeNormals(pclCloud, normalK_, normalRadius_);
537  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr pclCloudNormal(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
538  pcl::concatenateFields(*pclCloud, *normals, *pclCloudNormal);
539  if(filterNaNs_)
540  {
541  pclCloudNormal = rtabmap::util3d::removeNaNNormalsFromPointCloud(pclCloudNormal);
542  }
543  pcl::toROSMsg(*pclCloudNormal, rosCloud);
544  }
545  else
546  {
547  if(filterNaNs_ && !pclCloud->is_dense)
548  {
549  pclCloud = rtabmap::util3d::removeNaNFromPointCloud(pclCloud);
550  }
551  pcl::toROSMsg(*pclCloud, rosCloud);
552  }
553  rosCloud.header.stamp = header.stamp;
554  rosCloud.header.frame_id = header.frame_id;
555 
556  //publish the message
557  cloudPub_.publish(rosCloud);
558  }
559 
560 private:
561 
562  double maxDepth_;
563  double minDepth_;
564  double voxelSize_;
568  int normalK_;
571  std::vector<float> roiRatios_;
573 
575 
577 
581 
583 
588 
591 
594 
597 
600 
603 
606 };
607 
609 }
610 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string BAYER_GRBG8
void processAndPublish(pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pclCloud, pcl::IndicesPtr &indices, const std_msgs::Header &header)
int imageHeight() const
void disparityCallback(const sensor_msgs::ImageConstPtr &image, const stereo_msgs::DisparityImageConstPtr &imageDisparity, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
#define NODELET_ERROR(...)
f
rtabmap::SensorData rgbdImageFromROS(const rtabmap_ros::RGBDImageConstPtr &image)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::NodeHandle & getNodeHandle() const
data
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
void stereoCallback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &camInfoLeft, const sensor_msgs::CameraInfoConstPtr &camInfoRight)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
std::map< std::string, std::string > ParametersMap
const std::string TYPE_8UC1
ros::NodeHandle & getPrivateNodeHandle() const
#define ROS_WARN(...)
std::string uBool2Str(bool boolean)
image_transport::SubscriberFilter imageRight_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP 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)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncStereoPolicy
#define UASSERT(condition)
std::list< std::string > uSplit(const std::string &str, char separator=' ')
message_filters::Synchronizer< MyApproxSyncStereoPolicy > * approxSyncStereo_
message_filters::Synchronizer< MyExactSyncStereoPolicy > * exactSyncStereo_
std::string uNumber2Str(unsigned int number)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
image_transport::SubscriberFilter imageDepthSub_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
void depthCallback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
bool getParam(const std::string &key, std::string &s) const
message_filters::sync_policies::ExactTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyExactSyncDisparityPolicy
const std::string TYPE_32FC1
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP 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::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
cv::Rect RTABMAP_EXP computeRoi(const cv::Mat &image, const std::string &roiRatios)
CameraModel roi(const cv::Rect &roi) const
image_transport::SubscriberFilter imageSub_
const std::string TYPE_16UC1
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const std::string MONO16
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
double cx() const
#define false
pcl::IndicesPtr RTABMAP_EXP radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
static const ParametersMap & getDefaultParameters()
#define NODELET_INFO(...)
double cy() 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)
static WallTime now()
message_filters::Synchronizer< MyApproxSyncDisparityPolicy > * approxSyncDisparity_
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())
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
message_filters::Subscriber< stereo_msgs::DisparityImage > imageDisparitySub_
float uStr2Float(const std::string &str)
model
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyApproxSyncDisparityPolicy
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP 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())
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncStereoPolicy
int imageWidth() const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
uint32_t getNumSubscribers() const
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP 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)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
bool isValid() const
#define ROS_ERROR(...)
rtabmap::ParametersMap stereoBMParameters_
#define NODELET_DEBUG(...)
void rgbdImageCallback(const rtabmap_ros::RGBDImageConstPtr &image)
image_transport::SubscriberFilter imageLeft_
message_filters::Synchronizer< MyExactSyncDisparityPolicy > * exactSyncDisparity_
const std::string TYPE_16SC1


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40