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_util
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 = 1;
104  int syncQueueSize = 10;
105  bool approxSync = true;
106  std::string roiStr;
107  double approxSyncMaxInterval = 0.0;
108  pnh.param("approx_sync", approxSync, approxSync);
109  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
110  pnh.param("topic_queue_size", queueSize, queueSize);
111  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
112  {
113  pnh.param("queue_size", syncQueueSize, syncQueueSize);
114  ROS_WARN("Parameter \"queue_size\" has been renamed "
115  "to \"sync_queue_size\" and will be removed "
116  "in future versions! The value (%d) is copied to "
117  "\"sync_queue_size\".", syncQueueSize);
118  }
119  else
120  {
121  pnh.param("sync_queue_size", syncQueueSize, syncQueueSize);
122  }
123  pnh.param("max_depth", maxDepth_, maxDepth_);
124  pnh.param("min_depth", minDepth_, minDepth_);
125  pnh.param("voxel_size", voxelSize_, voxelSize_);
126  pnh.param("decimation", decimation_, decimation_);
127  pnh.param("noise_filter_radius", noiseFilterRadius_, noiseFilterRadius_);
128  pnh.param("noise_filter_min_neighbors", noiseFilterMinNeighbors_, noiseFilterMinNeighbors_);
129  pnh.param("normal_k", normalK_, normalK_);
130  pnh.param("normal_radius", normalRadius_, normalRadius_);
131  pnh.param("filter_nans", filterNaNs_, filterNaNs_);
132  pnh.param("roi_ratios", roiStr, roiStr);
133 
134  // Deprecated
135  if(pnh.hasParam("cut_left"))
136  {
137  ROS_ERROR("\"cut_left\" parameter is replaced by \"roi_ratios\". It will be ignored.");
138  }
139  if(pnh.hasParam("cut_right"))
140  {
141  ROS_ERROR("\"cut_right\" parameter is replaced by \"roi_ratios\". It will be ignored.");
142  }
143  if(pnh.hasParam("special_filter_close_object"))
144  {
145  ROS_ERROR("\"special_filter_close_object\" parameter is removed. This kind of processing "
146  "should be done before or after this nodelet. See old implementation here: "
147  "https://github.com/introlab/rtabmap_ros/blob/f0026b071c7c54fbcc71df778dd7e17f52f78fc4/src/nodelets/point_cloud_xyz.cpp#L178-L201.");
148  }
149 
150  //parse roi (region of interest)
151  roiRatios_.resize(4, 0);
152  if(!roiStr.empty())
153  {
154  std::list<std::string> strValues = uSplit(roiStr, ' ');
155  if(strValues.size() != 4)
156  {
157  ROS_ERROR("The number of values must be 4 (\"roi_ratios\"=\"%s\")", roiStr.c_str());
158  }
159  else
160  {
161  std::vector<float> tmpValues(4);
162  unsigned int i=0;
163  for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
164  {
165  tmpValues[i] = uStr2Float(*jter);
166  ++i;
167  }
168 
169  if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0f-tmpValues[1] &&
170  tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0f-tmpValues[0] &&
171  tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0f-tmpValues[3] &&
172  tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0f-tmpValues[2])
173  {
174  roiRatios_ = tmpValues;
175  }
176  else
177  {
178  ROS_ERROR("The roi ratios are not valid (\"roi_ratios\"=\"%s\")", roiStr.c_str());
179  }
180  }
181  }
182 
183  NODELET_INFO("Approximate time sync = %s", approxSync?"true":"false");
184 
185  if(approxSync)
186  {
188  if(approxSyncMaxInterval > 0.0)
189  approxSyncDepth_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
190  approxSyncDepth_->registerCallback(boost::bind(&PointCloudXYZ::callback, this, boost::placeholders::_1, boost::placeholders::_2));
191 
193  if(approxSyncMaxInterval > 0.0)
194  approxSyncDisparity_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
195  approxSyncDisparity_->registerCallback(boost::bind(&PointCloudXYZ::callbackDisparity, this, boost::placeholders::_1, boost::placeholders::_2));
196  }
197  else
198  {
200  exactSyncDepth_->registerCallback(boost::bind(&PointCloudXYZ::callback, this, boost::placeholders::_1, boost::placeholders::_2));
201 
203  exactSyncDisparity_->registerCallback(boost::bind(&PointCloudXYZ::callbackDisparity, this, boost::placeholders::_1, boost::placeholders::_2));
204  }
205 
206  ros::NodeHandle depth_nh(nh, "depth");
207  ros::NodeHandle depth_pnh(pnh, "depth");
208  image_transport::ImageTransport depth_it(depth_nh);
209  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
210 
211  imageDepthSub_.subscribe(depth_it, depth_nh.resolveName("image"), queueSize, hintsDepth);
212  cameraInfoSub_.subscribe(depth_nh, "camera_info", queueSize);
213 
214  disparitySub_.subscribe(nh, "disparity/image", queueSize);
215  disparityCameraInfoSub_.subscribe(nh, "disparity/camera_info", queueSize);
216 
217  cloudPub_ = nh.advertise<sensor_msgs::PointCloud2>("cloud", 1);
218  }
219 
220  void callback(
221  const sensor_msgs::ImageConstPtr& depthMsg,
222  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
223  {
224  if(depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)!=0 &&
225  depthMsg->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)!=0 &&
226  depthMsg->encoding.compare(sensor_msgs::image_encodings::MONO16)!=0)
227  {
228  NODELET_ERROR("Input type depth=32FC1,16UC1,MONO16");
229  return;
230  }
231 
233  {
235 
236  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(depthMsg);
237  cv::Rect roi = rtabmap::util2d::computeRoi(imageDepthPtr->image, roiRatios_);
238 
240 
241  pcl::PointCloud<pcl::PointXYZ>::Ptr pclCloud;
242 
243  cv::Mat depth = imageDepthPtr->image;
244  if( roiRatios_.size() == 4 &&
245  ((roiRatios_[0] > 0.0f && roiRatios_[0] <= 1.0f) ||
246  (roiRatios_[1] > 0.0f && roiRatios_[1] <= 1.0f) ||
247  (roiRatios_[2] > 0.0f && roiRatios_[2] <= 1.0f) ||
248  (roiRatios_[3] > 0.0f && roiRatios_[3] <= 1.0f)))
249  {
250  cv::Rect roiDepth = rtabmap::util2d::computeRoi(depth, roiRatios_);
251  cv::Rect roiRgb;
252  if(model.imageWidth() && model.imageHeight())
253  {
254  roiRgb = rtabmap::util2d::computeRoi(model.imageSize(), roiRatios_);
255  }
256  if( roiDepth.width%decimation_==0 &&
257  roiDepth.height%decimation_==0 &&
258  (roiRgb.width != 0 ||
259  (roiRgb.width%decimation_==0 &&
260  roiRgb.height%decimation_==0)))
261  {
262  depth = cv::Mat(depth, roiDepth);
263  if(model.imageWidth() != 0 && model.imageHeight() != 0)
264  {
265  model = model.roi(roiRgb);
266  }
267  else
268  {
269  model = model.roi(roiDepth);
270  }
271  }
272  else
273  {
274  NODELET_ERROR("Cannot apply ROI ratios [%f,%f,%f,%f] because resulting "
275  "dimension (depth=%dx%d rgb=%dx%d) cannot be divided exactly "
276  "by decimation parameter (%d). Ignoring ROI ratios...",
277  roiRatios_[0],
278  roiRatios_[1],
279  roiRatios_[2],
280  roiRatios_[3],
281  roiDepth.width,
282  roiDepth.height,
283  roiRgb.width,
284  roiRgb.height,
285  decimation_);
286  }
287  }
288 
289  pcl::IndicesPtr indices(new std::vector<int>);
291  depth,
292  model,
293  decimation_,
294  maxDepth_,
295  minDepth_,
296  indices.get());
297  processAndPublish(pclCloud, indices, depthMsg->header);
298 
299  NODELET_DEBUG("point_cloud_xyz from depth time = %f s", (ros::WallTime::now() - time).toSec());
300  }
301  }
302 
304  const stereo_msgs::DisparityImageConstPtr& disparityMsg,
305  const sensor_msgs::CameraInfoConstPtr& cameraInfo)
306  {
307  if(disparityMsg->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) !=0 &&
308  disparityMsg->image.encoding.compare(sensor_msgs::image_encodings::TYPE_16SC1) !=0)
309  {
310  NODELET_ERROR("Input type must be disparity=32FC1 or 16SC1");
311  return;
312  }
313 
314  cv::Mat disparity;
315  if(disparityMsg->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) == 0)
316  {
317  disparity = cv::Mat(disparityMsg->image.height, disparityMsg->image.width, CV_32FC1, const_cast<uchar*>(disparityMsg->image.data.data()));
318  }
319  else
320  {
321  disparity = cv::Mat(disparityMsg->image.height, disparityMsg->image.width, CV_16SC1, const_cast<uchar*>(disparityMsg->image.data.data()));
322  }
323 
325  {
327 
328  cv::Rect roi = rtabmap::util2d::computeRoi(disparity, roiRatios_);
329 
330  pcl::PointCloud<pcl::PointXYZ>::Ptr pclCloud;
332  UASSERT(disparity.cols == leftModel.imageWidth() && disparity.rows == leftModel.imageHeight());
333  rtabmap::StereoCameraModel stereoModel(disparityMsg->f, disparityMsg->f, leftModel.cx()-roiRatios_[0]*double(disparity.cols), leftModel.cy()-roiRatios_[2]*double(disparity.rows), disparityMsg->T);
334  pcl::IndicesPtr indices(new std::vector<int>);
336  cv::Mat(disparity, roi),
337  stereoModel,
338  decimation_,
339  maxDepth_,
340  minDepth_,
341  indices.get());
342 
343  processAndPublish(pclCloud, indices, disparityMsg->header);
344 
345  NODELET_DEBUG("point_cloud_xyz from disparity time = %f s", (ros::WallTime::now() - time).toSec());
346  }
347  }
348 
349  void processAndPublish(pcl::PointCloud<pcl::PointXYZ>::Ptr & pclCloud, pcl::IndicesPtr & indices, const std_msgs::Header & header)
350  {
351  if(indices->size() && voxelSize_ > 0.0)
352  {
353  pclCloud = rtabmap::util3d::voxelize(pclCloud, indices, voxelSize_);
354  pclCloud->is_dense = true;
355  }
356 
357  // Do radius filtering after voxel filtering ( a lot faster)
358  if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && noiseFilterRadius_ > 0.0 && noiseFilterMinNeighbors_ > 0)
359  {
360  if(pclCloud->is_dense)
361  {
363  }
364  else
365  {
367  }
368  pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZ>);
369  pcl::copyPointCloud(*pclCloud, *indices, *tmp);
370  pclCloud = tmp;
371  }
372 
373  sensor_msgs::PointCloud2 rosCloud;
374  if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && (normalK_ > 0 || normalRadius_ > 0.0f))
375  {
376  //compute normals
377  pcl::PointCloud<pcl::Normal>::Ptr normals = rtabmap::util3d::computeNormals(pclCloud, normalK_, normalRadius_);
378  pcl::PointCloud<pcl::PointNormal>::Ptr pclCloudNormal(new pcl::PointCloud<pcl::PointNormal>);
379  pcl::concatenateFields(*pclCloud, *normals, *pclCloudNormal);
380  if(filterNaNs_)
381  {
382  pclCloudNormal = rtabmap::util3d::removeNaNNormalsFromPointCloud(pclCloudNormal);
383  }
384  pcl::toROSMsg(*pclCloudNormal, rosCloud);
385  }
386  else
387  {
388  if(filterNaNs_ && !pclCloud->is_dense)
389  {
390  pclCloud = rtabmap::util3d::removeNaNFromPointCloud(pclCloud);
391  }
392  pcl::toROSMsg(*pclCloud, rosCloud);
393  }
394  rosCloud.header.stamp = header.stamp;
395  rosCloud.header.frame_id = header.frame_id;
396 
397  //publish the message
398  cloudPub_.publish(rosCloud);
399  }
400 
401 private:
402 
403  double maxDepth_;
404  double minDepth_;
405  double voxelSize_;
409  int normalK_;
412  std::vector<float> roiRatios_;
413 
415 
418 
421 
424 
427 
430 
433 
434 };
435 
437 }
438 
rtabmap_util::PointCloudXYZ::MyExactSyncDepthPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
Definition: point_cloud_xyz.cpp:428
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_util::PointCloudXYZ::cloudPub_
ros::Publisher cloudPub_
Definition: point_cloud_xyz.cpp:414
rtabmap::CameraModel::imageWidth
int imageWidth() const
NODELET_ERROR
#define NODELET_ERROR(...)
rtabmap::StereoCameraModel
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
image_transport::ImageTransport
message_filters::Synchronizer
rtabmap_util::PointCloudXYZ::approxSyncDisparity_
message_filters::Synchronizer< MyApproxSyncDisparityPolicy > * approxSyncDisparity_
Definition: point_cloud_xyz.cpp:426
rtabmap_util::PointCloudXYZ
Definition: point_cloud_xyz.cpp:66
boost::shared_ptr
rtabmap_util::PointCloudXYZ::noiseFilterMinNeighbors_
int noiseFilterMinNeighbors_
Definition: point_cloud_xyz.cpp:408
uchar
unsigned char uchar
pinhole_camera_model.h
rtabmap::util3d::removeNaNNormalsFromPointCloud
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
rtabmap_util::PointCloudXYZ::roiRatios_
std::vector< float > roiRatios_
Definition: point_cloud_xyz.cpp:412
rtabmap::CameraModel::cy
double cy() const
ros.h
rtabmap::CameraModel
rtabmap_conversions::cameraModelFromROS
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
ros::TransportHints
UStl.h
rtabmap_util::PointCloudXYZ::approxSyncDepth_
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
Definition: point_cloud_xyz.cpp:423
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
rtabmap_util::PointCloudXYZ::imageDepthSub_
image_transport::SubscriberFilter imageDepthSub_
Definition: point_cloud_xyz.cpp:416
rtabmap::util3d::radiusFiltering
pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
rtabmap_util::PointCloudXYZ::MyApproxSyncDisparityPolicy
message_filters::sync_policies::ApproximateTime< stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyApproxSyncDisparityPolicy
Definition: point_cloud_xyz.cpp:425
rtabmap_util::PointCloudXYZ::callback
void callback(const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
Definition: point_cloud_xyz.cpp:220
f
Vector3 f(-6, 1, 0.5)
rtabmap_util
Definition: MapsManager.h:49
rtabmap::util3d::cloudFromDepth
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT cloudFromDepth(const cv::Mat &imageDepth, const CameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
rtabmap_util::PointCloudXYZ::decimation_
int decimation_
Definition: point_cloud_xyz.cpp:406
indices
indices
rtabmap_util::PointCloudXYZ::callbackDisparity
void callbackDisparity(const stereo_msgs::DisparityImageConstPtr &disparityMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
Definition: point_cloud_xyz.cpp:303
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
message_filters::Subscriber< sensor_msgs::CameraInfo >
rtabmap_util::PointCloudXYZ::exactSyncDepth_
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
Definition: point_cloud_xyz.cpp:429
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
rtabmap_util::PointCloudXYZ::minDepth_
double minDepth_
Definition: point_cloud_xyz.cpp:404
rtabmap_util::PointCloudXYZ::PointCloudXYZ
PointCloudXYZ()
Definition: point_cloud_xyz.cpp:69
message_filters::sync_policies::ApproximateTime
rtabmap_util::PointCloudXYZ::~PointCloudXYZ
virtual ~PointCloudXYZ()
Definition: point_cloud_xyz.cpp:85
subscriber_filter.h
rtabmap_util::PointCloudXYZ::normalRadius_
double normalRadius_
Definition: point_cloud_xyz.cpp:410
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::PointCloudXYZ::voxelSize_
double voxelSize_
Definition: point_cloud_xyz.cpp:405
rtabmap_util::PointCloudXYZ::exactSyncDisparity_
message_filters::Synchronizer< MyExactSyncDisparityPolicy > * exactSyncDisparity_
Definition: point_cloud_xyz.cpp:432
subscriber.h
ros::WallTime::now
static WallTime now()
rtabmap_util::PointCloudXYZ::filterNaNs_
bool filterNaNs_
Definition: point_cloud_xyz.cpp:411
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
UASSERT
#define UASSERT(condition)
ROS_WARN
#define ROS_WARN(...)
rtabmap_util::PointCloudXYZ::disparityCameraInfoSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > disparityCameraInfoSub_
Definition: point_cloud_xyz.cpp:420
rtabmap_util::PointCloudXYZ::MyExactSyncDisparityPolicy
message_filters::sync_policies::ExactTime< stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyExactSyncDisparityPolicy
Definition: point_cloud_xyz.cpp:431
time
#define time
ros::WallTime
model
noiseModel::Diagonal::shared_ptr model
rtabmap_util::PointCloudXYZ::noiseFilterRadius_
double noiseFilterRadius_
Definition: point_cloud_xyz.cpp:407
image_transport.h
util3d_filtering.h
exact_time.h
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
rtabmap_util::PointCloudXYZ::MyApproxSyncDepthPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
Definition: point_cloud_xyz.cpp:422
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)
rtabmap_util::PointCloudXYZ::processAndPublish
void processAndPublish(pcl::PointCloud< pcl::PointXYZ >::Ptr &pclCloud, pcl::IndicesPtr &indices, const std_msgs::Header &header)
Definition: point_cloud_xyz.cpp:349
nodelet::Nodelet
rtabmap_util::PointCloudXYZ::maxDepth_
double maxDepth_
Definition: point_cloud_xyz.cpp:403
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
nodelet.h
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)
approximate_time.h
sensor_msgs::image_encodings::TYPE_16SC1
const std::string TYPE_16SC1
rtabmap_util::PointCloudXYZ::disparitySub_
message_filters::Subscriber< stereo_msgs::DisparityImage > disparitySub_
Definition: point_cloud_xyz.cpp:419
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())
rtabmap_util::PointCloudXYZ::cameraInfoSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: point_cloud_xyz.cpp:417
message_filters::sync_policies::ExactTime
header
const std::string header
uStr2Float
float uStr2Float(const std::string &str)
UConversion.h
MsgConversion.h
rtabmap_util::PointCloudXYZ::normalK_
int normalK_
Definition: point_cloud_xyz.cpp:409
rtabmap_util::PointCloudXYZ::onInit
virtual void onInit()
Definition: point_cloud_xyz.cpp:98
ros::Duration
i
int i
util3d.h
ros::NodeHandle
rtabmap::util3d::cloudFromDisparity
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT cloudFromDisparity(const cv::Mat &imageDisparity, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
NODELET_DEBUG
#define NODELET_DEBUG(...)
util2d.h
pcl_conversions.h


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