rgbdicp_odometry.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 
29 
31 #include <nodelet/nodelet.h>
32 
36 
39 
42 
43 #include <sensor_msgs/Image.h>
45 #include <cv_bridge/cv_bridge.h>
46 #include <sensor_msgs/LaserScan.h>
47 #include <sensor_msgs/PointCloud2.h>
49 
51 
52 #include <rtabmap/core/util3d.h>
56 #include <rtabmap/core/util2d.h>
59 #include <rtabmap/utilite/UStl.h>
60 
61 using namespace rtabmap;
62 
63 namespace rtabmap_ros
64 {
65 
67 {
68 public:
71  approxScanSync_(0),
72  exactScanSync_(0),
73  approxCloudSync_(0),
74  exactCloudSync_(0),
75  queueSize_(5),
76  scanCloudMaxPoints_(0),
77  scanVoxelSize_(0.0),
78  scanNormalK_(0),
79  scanNormalRadius_(0.0)
80  {
81  }
82 
83  virtual ~RGBDICPOdometry()
84  {
85  if(approxScanSync_)
86  {
87  delete approxScanSync_;
88  }
89  if(exactScanSync_)
90  {
91  delete exactScanSync_;
92  }
93  if(approxCloudSync_)
94  {
95  delete approxCloudSync_;
96  }
97  if(exactCloudSync_)
98  {
99  delete exactCloudSync_;
100  }
101  }
102 
103 private:
104 
105  virtual void onOdomInit()
106  {
107  ros::NodeHandle & nh = getNodeHandle();
108  ros::NodeHandle & pnh = getPrivateNodeHandle();
109 
110  bool approxSync = true;
111  bool subscribeScanCloud = false;
112  pnh.param("approx_sync", approxSync, approxSync);
113  pnh.param("queue_size", queueSize_, queueSize_);
114  pnh.param("subscribe_scan_cloud", subscribeScanCloud, subscribeScanCloud);
115  pnh.param("scan_cloud_max_points", scanCloudMaxPoints_, scanCloudMaxPoints_);
116  pnh.param("scan_voxel_size", scanVoxelSize_, scanVoxelSize_);
117  pnh.param("scan_normal_k", scanNormalK_, scanNormalK_);
118  if(pnh.hasParam("scan_cloud_normal_k") && !pnh.hasParam("scan_normal_k"))
119  {
120  ROS_WARN("rtabmap: Parameter \"scan_cloud_normal_k\" has been renamed to \"scan_normal_k\". "
121  "The value is still used. Use \"scan_normal_k\" to avoid this warning.");
122  pnh.param("scan_cloud_normal_k", scanNormalK_, scanNormalK_);
123  }
124  pnh.param("scan_normal_radius", scanNormalRadius_, scanNormalRadius_);
125 
126  NODELET_INFO("RGBDIcpOdometry: approx_sync = %s", approxSync?"true":"false");
127  NODELET_INFO("RGBDIcpOdometry: queue_size = %d", queueSize_);
128  NODELET_INFO("RGBDIcpOdometry: subscribe_scan_cloud = %s", subscribeScanCloud?"true":"false");
129  NODELET_INFO("RGBDIcpOdometry: scan_cloud_max_points = %d", scanCloudMaxPoints_);
130  NODELET_INFO("RGBDIcpOdometry: scan_voxel_size = %f", scanVoxelSize_);
131  NODELET_INFO("RGBDIcpOdometry: scan_normal_k = %d", scanNormalK_);
132  NODELET_INFO("RGBDIcpOdometry: scan_normal_radius = %f", scanNormalRadius_);
133 
134  ros::NodeHandle rgb_nh(nh, "rgb");
135  ros::NodeHandle depth_nh(nh, "depth");
136  ros::NodeHandle rgb_pnh(pnh, "rgb");
137  ros::NodeHandle depth_pnh(pnh, "depth");
138  image_transport::ImageTransport rgb_it(rgb_nh);
139  image_transport::ImageTransport depth_it(depth_nh);
140  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
141  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
142 
143  image_mono_sub_.subscribe(rgb_it, rgb_nh.resolveName("image"), 1, hintsRgb);
144  image_depth_sub_.subscribe(depth_it, depth_nh.resolveName("image"), 1, hintsDepth);
145  info_sub_.subscribe(rgb_nh, "camera_info", 1);
146 
147  std::string subscribedTopicsMsg;
148  if(subscribeScanCloud)
149  {
150  cloud_sub_.subscribe(nh, "scan_cloud", 1);
151  if(approxSync)
152  {
153  approxCloudSync_ = new message_filters::Synchronizer<MyApproxCloudSyncPolicy>(MyApproxCloudSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
154  approxCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, _1, _2, _3, _4));
155  }
156  else
157  {
158  exactCloudSync_ = new message_filters::Synchronizer<MyExactCloudSyncPolicy>(MyExactCloudSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
159  exactCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, _1, _2, _3, _4));
160  }
161 
162  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s,\n %s,\n %s, \n %s",
163  getName().c_str(),
164  approxSync?"approx":"exact",
165  image_mono_sub_.getTopic().c_str(),
166  image_depth_sub_.getTopic().c_str(),
167  info_sub_.getTopic().c_str(),
168  cloud_sub_.getTopic().c_str());
169  }
170  else
171  {
172  scan_sub_.subscribe(nh, "scan", 1);
173  if(approxSync)
174  {
175  approxScanSync_ = new message_filters::Synchronizer<MyApproxScanSyncPolicy>(MyApproxScanSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
176  approxScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, _1, _2, _3, _4));
177  }
178  else
179  {
180  exactScanSync_ = new message_filters::Synchronizer<MyExactScanSyncPolicy>(MyExactScanSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
181  exactScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, _1, _2, _3, _4));
182  }
183 
184  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s,\n %s,\n %s, \n %s",
185  getName().c_str(),
186  approxSync?"approx":"exact",
187  image_mono_sub_.getTopic().c_str(),
188  image_depth_sub_.getTopic().c_str(),
189  info_sub_.getTopic().c_str(),
190  scan_sub_.getTopic().c_str());
191  }
192  this->startWarningThread(subscribedTopicsMsg, approxSync);
193  }
194 
195  virtual void updateParameters(ParametersMap & parameters)
196  {
197  //make sure we are using Reg/Strategy=0
198  ParametersMap::iterator iter = parameters.find(Parameters::kRegStrategy());
199  if(iter != parameters.end() && iter->second.compare("0") != 0)
200  {
201  ROS_WARN("RGBDICP odometry works only with \"Reg/Strategy\"=2. Ignoring value %s.", iter->second.c_str());
202  }
203  uInsert(parameters, ParametersPair(Parameters::kRegStrategy(), "2"));
204  }
205 
207  const sensor_msgs::ImageConstPtr& image,
208  const sensor_msgs::ImageConstPtr& depth,
209  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
210  const sensor_msgs::LaserScanConstPtr& scanMsg)
211  {
212  sensor_msgs::PointCloud2ConstPtr cloudMsg;
213  callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
214  }
215 
217  const sensor_msgs::ImageConstPtr& image,
218  const sensor_msgs::ImageConstPtr& depth,
219  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
220  const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
221  {
222  sensor_msgs::LaserScanConstPtr scanMsg;
223  callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
224  }
225 
227  const sensor_msgs::ImageConstPtr& image,
228  const sensor_msgs::ImageConstPtr& depth,
229  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
230  const sensor_msgs::LaserScanConstPtr& scanMsg,
231  const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
232  {
233  callbackCalled();
234  if(!this->isPaused())
235  {
236  if(!(image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1) ==0 ||
237  image->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
238  image->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
239  image->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
240  image->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0 ||
241  image->encoding.compare(sensor_msgs::image_encodings::BGRA8) == 0 ||
242  image->encoding.compare(sensor_msgs::image_encodings::RGBA8) == 0 ||
243  image->encoding.compare(sensor_msgs::image_encodings::BAYER_GRBG8) == 0) ||
244  !(depth->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)==0 ||
245  depth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0 ||
246  depth->encoding.compare(sensor_msgs::image_encodings::MONO16)==0))
247  {
248  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8 (mono8 "
249  "recommended) and image_depth=16UC1,32FC1,mono16. Types detected: %s %s",
250  image->encoding.c_str(), depth->encoding.c_str());
251  return;
252  }
253 
254  // use the highest stamp to make sure that there will be no future interpolation required when synchronized with another node
255  ros::Time stamp = image->header.stamp > depth->header.stamp? image->header.stamp : depth->header.stamp;
256  if(scanMsg.get() != 0)
257  {
258  if(stamp < scanMsg->header.stamp)
259  {
260  stamp = scanMsg->header.stamp;
261  }
262  }
263  else if(cloudMsg.get() != 0)
264  {
265  if(stamp < cloudMsg->header.stamp)
266  {
267  stamp = cloudMsg->header.stamp;
268  }
269  }
270 
271  Transform localTransform = getTransform(this->frameId(), image->header.frame_id, stamp);
272  if(localTransform.isNull())
273  {
274  return;
275  }
276 
277  if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
278  {
279  rtabmap::CameraModel rtabmapModel = rtabmap_ros::cameraModelFromROS(*cameraInfo, localTransform);
280  cv_bridge::CvImagePtr ptrImage = cv_bridge::toCvCopy(image, image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1)==0?"":"mono8");
281  cv_bridge::CvImagePtr ptrDepth = cv_bridge::toCvCopy(depth);
282 
283  cv::Mat scan;
284  Transform localScanTransform = Transform::getIdentity();
285  int maxLaserScans = 0;
286  if(scanMsg.get() != 0)
287  {
288  // make sure the frame of the laser is updated too
289  localScanTransform = getTransform(this->frameId(),
290  scanMsg->header.frame_id,
291  scanMsg->header.stamp + ros::Duration().fromSec(scanMsg->ranges.size()*scanMsg->time_increment));
292  if(localScanTransform.isNull())
293  {
294  ROS_ERROR("TF of received laser scan topic at time %fs is not set, aborting odometry update.", scanMsg->header.stamp.toSec());
295  return;
296  }
297 
298  //transform in frameId_ frame
299  sensor_msgs::PointCloud2 scanOut;
301  projection.transformLaserScanToPointCloud(scanMsg->header.frame_id, *scanMsg, scanOut, this->tfListener());
302  pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(new pcl::PointCloud<pcl::PointXYZ>);
303  pcl::fromROSMsg(scanOut, *pclScan);
304  pclScan->is_dense = true;
305 
306  maxLaserScans = (int)scanMsg->ranges.size();
307  if(pclScan->size())
308  {
309  if(scanVoxelSize_ > 0.0f)
310  {
311  float pointsBeforeFiltering = (float)pclScan->size();
312  pclScan = util3d::voxelize(pclScan, scanVoxelSize_);
313  float ratio = float(pclScan->size()) / pointsBeforeFiltering;
314  maxLaserScans = int(float(maxLaserScans) * ratio);
315  }
316  if(scanNormalK_ > 0 || scanNormalRadius_>0.0f)
317  {
318  //compute normals
319  pcl::PointCloud<pcl::Normal>::Ptr normals;
320  if(scanVoxelSize_ > 0.0f)
321  {
322  normals = util3d::computeNormals2D(pclScan, scanNormalK_, scanNormalRadius_);
323  }
324  else
325  {
326  normals = util3d::computeFastOrganizedNormals2D(pclScan, scanNormalK_, scanNormalRadius_);
327  }
328  pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(new pcl::PointCloud<pcl::PointNormal>);
329  pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
330  scan = util3d::laserScan2dFromPointCloud(*pclScanNormal);
331  }
332  else
333  {
334  scan = util3d::laserScan2dFromPointCloud(*pclScan);
335  }
336  }
337  }
338  else if(cloudMsg.get() != 0)
339  {
340  bool containNormals = false;
341  if(scanVoxelSize_ == 0.0f)
342  {
343  for(unsigned int i=0; i<cloudMsg->fields.size(); ++i)
344  {
345  if(cloudMsg->fields[i].name.compare("normal_x") == 0)
346  {
347  containNormals = true;
348  break;
349  }
350  }
351  }
352  localScanTransform = getTransform(this->frameId(), cloudMsg->header.frame_id, cloudMsg->header.stamp);
353  if(localScanTransform.isNull())
354  {
355  ROS_ERROR("TF of received scan cloud at time %fs is not set, aborting rtabmap update.", cloudMsg->header.stamp.toSec());
356  return;
357  }
358 
359  maxLaserScans = scanCloudMaxPoints_;
360  if(containNormals)
361  {
362  pcl::PointCloud<pcl::PointNormal>::Ptr pclScan(new pcl::PointCloud<pcl::PointNormal>);
363  pcl::fromROSMsg(*cloudMsg, *pclScan);
364  if(!pclScan->is_dense)
365  {
366  pclScan = util3d::removeNaNNormalsFromPointCloud(pclScan);
367  }
368  scan = util3d::laserScanFromPointCloud(*pclScan);
369  }
370  else
371  {
372  pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(new pcl::PointCloud<pcl::PointXYZ>);
373  pcl::fromROSMsg(*cloudMsg, *pclScan);
374  if(!pclScan->is_dense)
375  {
376  pclScan = util3d::removeNaNFromPointCloud(pclScan);
377  }
378 
379  if(pclScan->size())
380  {
381  if(scanVoxelSize_ > 0.0f)
382  {
383  float pointsBeforeFiltering = (float)pclScan->size();
384  pclScan = util3d::voxelize(pclScan, scanVoxelSize_);
385  float ratio = float(pclScan->size()) / pointsBeforeFiltering;
386  maxLaserScans = int(float(maxLaserScans) * ratio);
387  }
388  if(scanNormalK_ > 0 || scanNormalRadius_>0.0f)
389  {
390  //compute normals
391  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(pclScan, scanNormalK_, scanNormalRadius_);
392  pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(new pcl::PointCloud<pcl::PointNormal>);
393  pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
394  scan = util3d::laserScanFromPointCloud(*pclScanNormal);
395  }
396  else
397  {
398  scan = util3d::laserScanFromPointCloud(*pclScan);
399  }
400  }
401  }
402  }
403 
404  rtabmap::SensorData data(
406  scanMsg.get() != 0 || cloudMsg.get() != 0?maxLaserScans:0,
407  scanMsg.get() != 0?scanMsg->range_max:0,
408  localScanTransform),
409  ptrImage->image,
410  ptrDepth->image,
411  rtabmapModel,
412  0,
414 
415  this->processData(data, stamp);
416  }
417  }
418  }
419 
420 protected:
421  virtual void flushCallbacks()
422  {
423  // flush callbacks
424  if(approxScanSync_)
425  {
426  delete approxScanSync_;
427  approxScanSync_ = new message_filters::Synchronizer<MyApproxScanSyncPolicy>(MyApproxScanSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
428  approxScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, _1, _2, _3, _4));
429  }
430  if(exactScanSync_)
431  {
432  delete exactScanSync_;
433  exactScanSync_ = new message_filters::Synchronizer<MyExactScanSyncPolicy>(MyExactScanSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
434  exactScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, _1, _2, _3, _4));
435  }
436  if(approxCloudSync_)
437  {
438  delete approxCloudSync_;
439  approxCloudSync_ = new message_filters::Synchronizer<MyApproxCloudSyncPolicy>(MyApproxCloudSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
440  approxCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, _1, _2, _3, _4));
441  }
442  if(exactCloudSync_)
443  {
444  delete exactCloudSync_;
445  exactCloudSync_ = new message_filters::Synchronizer<MyExactCloudSyncPolicy>(MyExactCloudSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
446  exactCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, _1, _2, _3, _4));
447  }
448  }
449 
450 private:
469 };
470 
472 
473 }
const std::string BAYER_GRBG8
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true)
void callbackScan(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::LaserScanConstPtr &scanMsg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloud_sub_
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_EXP computeNormals2D(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
f
image_transport::SubscriberFilter image_mono_sub_
message_filters::Synchronizer< MyApproxScanSyncPolicy > * approxScanSync_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > MyApproxCloudSyncPolicy
std::pair< std::string, std::string > ParametersPair
std::string resolveName(const std::string &name, bool remap=true) const
static Transform getIdentity()
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
image_transport::SubscriberFilter image_depth_sub_
message_filters::Subscriber< sensor_msgs::LaserScan > scan_sub_
std::string getName(void *handle)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > MyExactScanSyncPolicy
message_filters::Subscriber< sensor_msgs::CameraInfo > info_sub_
const std::string TYPE_8UC1
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
message_filters::Synchronizer< MyExactCloudSyncPolicy > * exactCloudSync_
#define ROS_WARN(...)
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::RGBDICPOdometry, nodelet::Nodelet)
void callbackCloud(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
void callbackCommon(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
cv::Mat RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform(), bool filterNaNs=true)
#define true
bool isNull() const
Connection registerCallback(C &callback)
message_filters::Synchronizer< MyExactScanSyncPolicy > * exactScanSync_
message_filters::Synchronizer< MyApproxCloudSyncPolicy > * approxCloudSync_
Duration & fromSec(double t)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const std::string TYPE_32FC1
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > MyExactCloudSyncPolicy
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string TYPE_16UC1
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
QMap< QString, QVariant > ParametersMap
const std::string MONO16
virtual void updateParameters(ParametersMap &parameters)
#define false
#define NODELET_INFO(...)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > MyApproxScanSyncPolicy
double timestampFromROS(const ros::Time &stamp)
const std::string header
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
void transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default)
bool hasParam(const std::string &key) 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(...)
static LaserScan backwardCompatibility(const cv::Mat &oldScanFormat, int maxPoints=0, int maxRange=0, const Transform &localTransform=Transform::getIdentity())
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04