point_cloud_xyz.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 
33 
34 #include <pcl/point_cloud.h>
35 #include <pcl/point_types.h>
37 
38 #include <sensor_msgs/PointCloud2.h>
39 #include <sensor_msgs/Image.h>
41 #include <sensor_msgs/CameraInfo.h>
42 #include <stereo_msgs/DisparityImage.h>
43 
46 
48 
52 
53 #include <cv_bridge/cv_bridge.h>
54 #include <opencv2/highgui/highgui.hpp>
55 
56 #include "rtabmap/core/util2d.h"
57 #include "rtabmap/core/util3d.h"
61 #include "rtabmap/utilite/UStl.h"
62 
63 namespace rtabmap_ros
64 {
65 
67 {
68 public:
70  maxDepth_(0.0),
71  minDepth_(0.0),
72  voxelSize_(0.0),
73  decimation_(1),
74  noiseFilterRadius_(0.0),
76  normalK_(0),
77  normalRadius_(0.0),
81  exactSyncDepth_(0),
83  {}
84 
85  virtual ~PointCloudXYZ()
86  {
88  delete approxSyncDepth_;
90  delete approxSyncDisparity_;
91  if(exactSyncDepth_)
92  delete exactSyncDepth_;
94  delete exactSyncDisparity_;
95  }
96 
97 private:
98  virtual void onInit()
99  {
102 
103  int queueSize = 10;
104  bool approxSync = true;
105  std::string roiStr;
106  double approxSyncMaxInterval = 0.0;
107  pnh.param("approx_sync", approxSync, approxSync);
108  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
109  pnh.param("queue_size", queueSize, queueSize);
110  pnh.param("max_depth", maxDepth_, maxDepth_);
111  pnh.param("min_depth", minDepth_, minDepth_);
112  pnh.param("voxel_size", voxelSize_, voxelSize_);
113  pnh.param("decimation", decimation_, decimation_);
114  pnh.param("noise_filter_radius", noiseFilterRadius_, noiseFilterRadius_);
115  pnh.param("noise_filter_min_neighbors", noiseFilterMinNeighbors_, noiseFilterMinNeighbors_);
116  pnh.param("normal_k", normalK_, normalK_);
117  pnh.param("normal_radius", normalRadius_, normalRadius_);
118  pnh.param("filter_nans", filterNaNs_, filterNaNs_);
119  pnh.param("roi_ratios", roiStr, roiStr);
120 
121  // Deprecated
122  if(pnh.hasParam("cut_left"))
123  {
124  ROS_ERROR("\"cut_left\" parameter is replaced by \"roi_ratios\". It will be ignored.");
125  }
126  if(pnh.hasParam("cut_right"))
127  {
128  ROS_ERROR("\"cut_right\" parameter is replaced by \"roi_ratios\". It will be ignored.");
129  }
130  if(pnh.hasParam("special_filter_close_object"))
131  {
132  ROS_ERROR("\"special_filter_close_object\" parameter is removed. This kind of processing "
133  "should be done before or after this nodelet. See old implementation here: "
134  "https://github.com/introlab/rtabmap_ros/blob/f0026b071c7c54fbcc71df778dd7e17f52f78fc4/src/nodelets/point_cloud_xyz.cpp#L178-L201.");
135  }
136 
137  //parse roi (region of interest)
138  roiRatios_.resize(4, 0);
139  if(!roiStr.empty())
140  {
141  std::list<std::string> strValues = uSplit(roiStr, ' ');
142  if(strValues.size() != 4)
143  {
144  ROS_ERROR("The number of values must be 4 (\"roi_ratios\"=\"%s\")", roiStr.c_str());
145  }
146  else
147  {
148  std::vector<float> tmpValues(4);
149  unsigned int i=0;
150  for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
151  {
152  tmpValues[i] = uStr2Float(*jter);
153  ++i;
154  }
155 
156  if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0f-tmpValues[1] &&
157  tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0f-tmpValues[0] &&
158  tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0f-tmpValues[3] &&
159  tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0f-tmpValues[2])
160  {
161  roiRatios_ = tmpValues;
162  }
163  else
164  {
165  ROS_ERROR("The roi ratios are not valid (\"roi_ratios\"=\"%s\")", roiStr.c_str());
166  }
167  }
168  }
169 
170  NODELET_INFO("Approximate time sync = %s", approxSync?"true":"false");
171 
172  if(approxSync)
173  {
175  if(approxSyncMaxInterval > 0.0)
176  approxSyncDepth_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
177  approxSyncDepth_->registerCallback(boost::bind(&PointCloudXYZ::callback, this, boost::placeholders::_1, boost::placeholders::_2));
178 
180  if(approxSyncMaxInterval > 0.0)
181  approxSyncDisparity_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
182  approxSyncDisparity_->registerCallback(boost::bind(&PointCloudXYZ::callbackDisparity, this, boost::placeholders::_1, boost::placeholders::_2));
183  }
184  else
185  {
187  exactSyncDepth_->registerCallback(boost::bind(&PointCloudXYZ::callback, this, boost::placeholders::_1, boost::placeholders::_2));
188 
190  exactSyncDisparity_->registerCallback(boost::bind(&PointCloudXYZ::callbackDisparity, this, boost::placeholders::_1, boost::placeholders::_2));
191  }
192 
193  ros::NodeHandle depth_nh(nh, "depth");
194  ros::NodeHandle depth_pnh(pnh, "depth");
195  image_transport::ImageTransport depth_it(depth_nh);
196  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
197 
198  imageDepthSub_.subscribe(depth_it, depth_nh.resolveName("image"), 1, hintsDepth);
199  cameraInfoSub_.subscribe(depth_nh, "camera_info", 1);
200 
201  disparitySub_.subscribe(nh, "disparity/image", 1);
202  disparityCameraInfoSub_.subscribe(nh, "disparity/camera_info", 1);
203 
204  cloudPub_ = nh.advertise<sensor_msgs::PointCloud2>("cloud", 1);
205  }
206 
207  void callback(
208  const sensor_msgs::ImageConstPtr& depthMsg,
209  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
210  {
211  if(depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)!=0 &&
212  depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)!=0 &&
213  depthMsg->encoding.compare(sensor_msgs::image_encodings::MONO16)!=0)
214  {
215  NODELET_ERROR("Input type depth=32FC1,16UC1,MONO16");
216  return;
217  }
218 
220  {
222 
223  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(depthMsg);
224  cv::Rect roi = rtabmap::util2d::computeRoi(imageDepthPtr->image, roiRatios_);
225 
227 
228  pcl::PointCloud<pcl::PointXYZ>::Ptr pclCloud;
229 
230  cv::Mat depth = imageDepthPtr->image;
231  if( roiRatios_.size() == 4 &&
232  ((roiRatios_[0] > 0.0f && roiRatios_[0] <= 1.0f) ||
233  (roiRatios_[1] > 0.0f && roiRatios_[1] <= 1.0f) ||
234  (roiRatios_[2] > 0.0f && roiRatios_[2] <= 1.0f) ||
235  (roiRatios_[3] > 0.0f && roiRatios_[3] <= 1.0f)))
236  {
237  cv::Rect roiDepth = rtabmap::util2d::computeRoi(depth, roiRatios_);
238  cv::Rect roiRgb;
239  if(model.imageWidth() && model.imageHeight())
240  {
242  }
243  if( roiDepth.width%decimation_==0 &&
244  roiDepth.height%decimation_==0 &&
245  (roiRgb.width != 0 ||
246  (roiRgb.width%decimation_==0 &&
247  roiRgb.height%decimation_==0)))
248  {
249  depth = cv::Mat(depth, roiDepth);
250  if(model.imageWidth() != 0 && model.imageHeight() != 0)
251  {
252  model = model.roi(roiRgb);
253  }
254  else
255  {
256  model = model.roi(roiDepth);
257  }
258  }
259  else
260  {
261  NODELET_ERROR("Cannot apply ROI ratios [%f,%f,%f,%f] because resulting "
262  "dimension (depth=%dx%d rgb=%dx%d) cannot be divided exactly "
263  "by decimation parameter (%d). Ignoring ROI ratios...",
264  roiRatios_[0],
265  roiRatios_[1],
266  roiRatios_[2],
267  roiRatios_[3],
268  roiDepth.width,
269  roiDepth.height,
270  roiRgb.width,
271  roiRgb.height,
272  decimation_);
273  }
274  }
275 
276  pcl::IndicesPtr indices(new std::vector<int>);
278  depth,
279  model,
280  decimation_,
281  maxDepth_,
282  minDepth_,
283  indices.get());
284  processAndPublish(pclCloud, indices, depthMsg->header);
285 
286  NODELET_DEBUG("point_cloud_xyz from depth time = %f s", (ros::WallTime::now() - time).toSec());
287  }
288  }
289 
291  const stereo_msgs::DisparityImageConstPtr& disparityMsg,
292  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
293  {
294  if(disparityMsg->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) !=0 &&
295  disparityMsg->image.encoding.compare(sensor_msgs::image_encodings::TYPE_16SC1) !=0)
296  {
297  NODELET_ERROR("Input type must be disparity=32FC1 or 16SC1");
298  return;
299  }
300 
301  cv::Mat disparity;
302  if(disparityMsg->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) == 0)
303  {
304  disparity = cv::Mat(disparityMsg->image.height, disparityMsg->image.width, CV_32FC1, const_cast<uchar*>(disparityMsg->image.data.data()));
305  }
306  else
307  {
308  disparity = cv::Mat(disparityMsg->image.height, disparityMsg->image.width, CV_16SC1, const_cast<uchar*>(disparityMsg->image.data.data()));
309  }
310 
312  {
314 
315  cv::Rect roi = rtabmap::util2d::computeRoi(disparity, roiRatios_);
316 
317  pcl::PointCloud<pcl::PointXYZ>::Ptr pclCloud;
318  rtabmap::CameraModel leftModel = rtabmap_ros::cameraModelFromROS(*cameraInfo);
319  UASSERT(disparity.cols == leftModel.imageWidth() && disparity.rows == leftModel.imageHeight());
320  rtabmap::StereoCameraModel stereoModel(disparityMsg->f, disparityMsg->f, leftModel.cx()-roiRatios_[0]*double(disparity.cols), leftModel.cy()-roiRatios_[2]*double(disparity.rows), disparityMsg->T);
321  pcl::IndicesPtr indices(new std::vector<int>);
323  cv::Mat(disparity, roi),
324  stereoModel,
325  decimation_,
326  maxDepth_,
327  minDepth_,
328  indices.get());
329 
330  processAndPublish(pclCloud, indices, disparityMsg->header);
331 
332  NODELET_DEBUG("point_cloud_xyz from disparity time = %f s", (ros::WallTime::now() - time).toSec());
333  }
334  }
335 
336  void processAndPublish(pcl::PointCloud<pcl::PointXYZ>::Ptr & pclCloud, pcl::IndicesPtr & indices, const std_msgs::Header & header)
337  {
338  if(indices->size() && voxelSize_ > 0.0)
339  {
340  pclCloud = rtabmap::util3d::voxelize(pclCloud, indices, voxelSize_);
341  pclCloud->is_dense = true;
342  }
343 
344  // Do radius filtering after voxel filtering ( a lot faster)
345  if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && noiseFilterRadius_ > 0.0 && noiseFilterMinNeighbors_ > 0)
346  {
347  if(pclCloud->is_dense)
348  {
350  }
351  else
352  {
354  }
355  pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZ>);
356  pcl::copyPointCloud(*pclCloud, *indices, *tmp);
357  pclCloud = tmp;
358  }
359 
360  sensor_msgs::PointCloud2 rosCloud;
361  if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && (normalK_ > 0 || normalRadius_ > 0.0f))
362  {
363  //compute normals
364  pcl::PointCloud<pcl::Normal>::Ptr normals = rtabmap::util3d::computeNormals(pclCloud, normalK_, normalRadius_);
365  pcl::PointCloud<pcl::PointNormal>::Ptr pclCloudNormal(new pcl::PointCloud<pcl::PointNormal>);
366  pcl::concatenateFields(*pclCloud, *normals, *pclCloudNormal);
367  if(filterNaNs_)
368  {
369  pclCloudNormal = rtabmap::util3d::removeNaNNormalsFromPointCloud(pclCloudNormal);
370  }
371  pcl::toROSMsg(*pclCloudNormal, rosCloud);
372  }
373  else
374  {
375  if(filterNaNs_ && !pclCloud->is_dense)
376  {
377  pclCloud = rtabmap::util3d::removeNaNFromPointCloud(pclCloud);
378  }
379  pcl::toROSMsg(*pclCloud, rosCloud);
380  }
381  rosCloud.header.stamp = header.stamp;
382  rosCloud.header.frame_id = header.frame_id;
383 
384  //publish the message
385  cloudPub_.publish(rosCloud);
386  }
387 
388 private:
389 
390  double maxDepth_;
391  double minDepth_;
392  double voxelSize_;
396  int normalK_;
399  std::vector<float> roiRatios_;
400 
402 
405 
408 
411 
414 
417 
420 
421 };
422 
424 }
425 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::vector< float > roiRatios_
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDisparity(const cv::Mat &imageDisparity, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
void callbackDisparity(const stereo_msgs::DisparityImageConstPtr &disparityMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
const cv::Size & imageSize() const
int imageHeight() const
#define NODELET_ERROR(...)
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
f
ros::NodeHandle & getNodeHandle() const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
image_transport::SubscriberFilter imageDepthSub_
message_filters::sync_policies::ApproximateTime< stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyApproxSyncDisparityPolicy
message_filters::Synchronizer< MyApproxSyncDisparityPolicy > * approxSyncDisparity_
ros::NodeHandle & getPrivateNodeHandle() const
message_filters::Subscriber< sensor_msgs::CameraInfo > disparityCameraInfoSub_
message_filters::Synchronizer< MyExactSyncDisparityPolicy > * exactSyncDisparity_
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDepth(const cv::Mat &imageDepth, const CameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
#define UASSERT(condition)
message_filters::sync_policies::ExactTime< stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyExactSyncDisparityPolicy
void processAndPublish(pcl::PointCloud< pcl::PointXYZ >::Ptr &pclCloud, pcl::IndicesPtr &indices, const std_msgs::Header &header)
std::list< std::string > uSplit(const std::string &str, char separator=' ')
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::Subscriber< stereo_msgs::DisparityImage > disparitySub_
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
const std::string TYPE_32FC1
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)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
CameraModel roi(const cv::Rect &roi) const
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
bool hasParam(const std::string &key) const
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)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
#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()
void callback(const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
float uStr2Float(const std::string &str)
model
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
int imageWidth() const
uint32_t getNumSubscribers() const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
#define ROS_ERROR(...)
#define NODELET_DEBUG(...)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
const std::string TYPE_16SC1


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