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_odom
64 {
65 
67 {
68 public:
71  approxScanSync_(0),
72  exactScanSync_(0),
73  approxCloudSync_(0),
74  exactCloudSync_(0),
75  queueSize_(1),
76  syncQueueSize_(5),
77  keepColor_(false),
78  scanCloudMaxPoints_(0),
79  scanVoxelSize_(0.0),
80  scanNormalK_(0),
81  scanNormalRadius_(0.0)
82  {
83  }
84 
85  virtual ~RGBDICPOdometry()
86  {
87  if(approxScanSync_)
88  {
89  delete approxScanSync_;
90  }
91  if(exactScanSync_)
92  {
93  delete exactScanSync_;
94  }
95  if(approxCloudSync_)
96  {
97  delete approxCloudSync_;
98  }
99  if(exactCloudSync_)
100  {
101  delete exactCloudSync_;
102  }
103  }
104 
105 private:
106 
107  virtual void onOdomInit()
108  {
109  ros::NodeHandle & nh = getNodeHandle();
110  ros::NodeHandle & pnh = getPrivateNodeHandle();
111 
112  bool approxSync = true;
113  bool subscribeScanCloud = false;
114  double approxSyncMaxInterval = 0.0;
115  pnh.param("approx_sync", approxSync, approxSync);
116  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
117  pnh.param("topic_queue_size", queueSize_, queueSize_);
118  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
119  {
120  pnh.param("queue_size", syncQueueSize_, syncQueueSize_);
121  ROS_WARN("Parameter \"queue_size\" has been renamed "
122  "to \"sync_queue_size\" and will be removed "
123  "in future versions! The value (%d) is still copied to "
124  "\"sync_queue_size\".", syncQueueSize_);
125  }
126  else
127  {
128  pnh.param("sync_queue_size", syncQueueSize_, syncQueueSize_);
129  }
130  pnh.param("subscribe_scan_cloud", subscribeScanCloud, subscribeScanCloud);
131  pnh.param("scan_cloud_max_points", scanCloudMaxPoints_, scanCloudMaxPoints_);
132  pnh.param("scan_voxel_size", scanVoxelSize_, scanVoxelSize_);
133  pnh.param("scan_normal_k", scanNormalK_, scanNormalK_);
134  if(pnh.hasParam("scan_cloud_normal_k") && !pnh.hasParam("scan_normal_k"))
135  {
136  ROS_WARN("rtabmap: Parameter \"scan_cloud_normal_k\" has been renamed to \"scan_normal_k\". "
137  "The value is still used. Use \"scan_normal_k\" to avoid this warning.");
138  pnh.param("scan_cloud_normal_k", scanNormalK_, scanNormalK_);
139  }
140  pnh.param("scan_normal_radius", scanNormalRadius_, scanNormalRadius_);
141  pnh.param("keep_color", keepColor_, keepColor_);
142 
143  NODELET_INFO("RGBDIcpOdometry: approx_sync = %s", approxSync?"true":"false");
144  if(approxSync)
145  NODELET_INFO("RGBDIcpOdometry: approx_sync_max_interval = %f", approxSyncMaxInterval);
146  NODELET_INFO("RGBDIcpOdometry: topic_queue_size = %d", queueSize_);
147  NODELET_INFO("RGBDIcpOdometry: sync_queue_size = %d", syncQueueSize_);
148  NODELET_INFO("RGBDIcpOdometry: subscribe_scan_cloud = %s", subscribeScanCloud?"true":"false");
149  NODELET_INFO("RGBDIcpOdometry: scan_cloud_max_points = %d", scanCloudMaxPoints_);
150  NODELET_INFO("RGBDIcpOdometry: scan_voxel_size = %f", scanVoxelSize_);
151  NODELET_INFO("RGBDIcpOdometry: scan_normal_k = %d", scanNormalK_);
152  NODELET_INFO("RGBDIcpOdometry: scan_normal_radius = %f", scanNormalRadius_);
153  NODELET_INFO("RGBDIcpOdometry: keep_color = %s", keepColor_?"true":"false");
154 
155  ros::NodeHandle rgb_nh(nh, "rgb");
156  ros::NodeHandle depth_nh(nh, "depth");
157  ros::NodeHandle rgb_pnh(pnh, "rgb");
158  ros::NodeHandle depth_pnh(pnh, "depth");
159  image_transport::ImageTransport rgb_it(rgb_nh);
160  image_transport::ImageTransport depth_it(depth_nh);
161  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
162  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
163 
164  image_mono_sub_.subscribe(rgb_it, rgb_nh.resolveName("image"), queueSize_, hintsRgb);
165  image_depth_sub_.subscribe(depth_it, depth_nh.resolveName("image"), queueSize_, hintsDepth);
166  info_sub_.subscribe(rgb_nh, "camera_info", queueSize_);
167 
168  std::string subscribedTopicsMsg;
169  if(subscribeScanCloud)
170  {
171  cloud_sub_.subscribe(nh, "scan_cloud", queueSize_);
172  if(approxSync)
173  {
174  approxCloudSync_ = new message_filters::Synchronizer<MyApproxCloudSyncPolicy>(MyApproxCloudSyncPolicy(syncQueueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
175  if(approxSyncMaxInterval > 0.0)
176  approxCloudSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
177  approxCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
178  }
179  else
180  {
181  exactCloudSync_ = new message_filters::Synchronizer<MyExactCloudSyncPolicy>(MyExactCloudSyncPolicy(syncQueueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
182  exactCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
183  }
184 
185  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync%s):\n %s,\n %s,\n %s, \n %s",
186  getName().c_str(),
187  approxSync?"approx":"exact",
188  approxSync&&approxSyncMaxInterval!=0.0?uFormat(", max interval=%fs", approxSyncMaxInterval).c_str():"",
189  image_mono_sub_.getTopic().c_str(),
190  image_depth_sub_.getTopic().c_str(),
191  info_sub_.getTopic().c_str(),
192  cloud_sub_.getTopic().c_str());
193  }
194  else
195  {
196  scan_sub_.subscribe(nh, "scan", queueSize_);
197  if(approxSync)
198  {
199  approxScanSync_ = new message_filters::Synchronizer<MyApproxScanSyncPolicy>(MyApproxScanSyncPolicy(syncQueueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
200  if(approxSyncMaxInterval > 0.0)
201  approxScanSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
202  approxScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
203  }
204  else
205  {
206  exactScanSync_ = new message_filters::Synchronizer<MyExactScanSyncPolicy>(MyExactScanSyncPolicy(syncQueueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
207  exactScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
208  }
209 
210  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s \\\n %s",
211  getName().c_str(),
212  approxSync?"approx":"exact",
213  approxSync&&approxSyncMaxInterval!=0.0?uFormat(", max interval=%fs", approxSyncMaxInterval).c_str():"",
214  image_mono_sub_.getTopic().c_str(),
215  image_depth_sub_.getTopic().c_str(),
216  info_sub_.getTopic().c_str(),
217  scan_sub_.getTopic().c_str());
218  }
219  initDiagnosticMsg(subscribedTopicsMsg, approxSync);
220  }
221 
222  virtual void updateParameters(ParametersMap & parameters)
223  {
224  //make sure we are using Reg/Strategy=0
225  ParametersMap::iterator iter = parameters.find(Parameters::kRegStrategy());
226  if(iter != parameters.end() && iter->second.compare("2") != 0)
227  {
228  ROS_WARN("RGBDICP odometry works only with \"Reg/Strategy\"=2. Ignoring value %s.", iter->second.c_str());
229  }
230  uInsert(parameters, ParametersPair(Parameters::kRegStrategy(), "2"));
231  }
232 
234  const sensor_msgs::ImageConstPtr& image,
235  const sensor_msgs::ImageConstPtr& depth,
236  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
237  const sensor_msgs::LaserScanConstPtr& scanMsg)
238  {
239  sensor_msgs::PointCloud2ConstPtr cloudMsg;
240  callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
241  }
242 
244  const sensor_msgs::ImageConstPtr& image,
245  const sensor_msgs::ImageConstPtr& depth,
246  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
247  const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
248  {
249  sensor_msgs::LaserScanConstPtr scanMsg;
250  callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
251  }
252 
254  const sensor_msgs::ImageConstPtr& image,
255  const sensor_msgs::ImageConstPtr& depth,
256  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
257  const sensor_msgs::LaserScanConstPtr& scanMsg,
258  const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
259  {
260  if(!this->isPaused())
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  !(depth->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)==0 ||
271  depth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0 ||
272  depth->encoding.compare(sensor_msgs::image_encodings::MONO16)==0))
273  {
274  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8,rgba8,bgra8 (mono8 "
275  "recommended) and image_depth=16UC1,32FC1,mono16. Types detected: %s %s",
276  image->encoding.c_str(), depth->encoding.c_str());
277  return;
278  }
279 
280  // use the highest stamp to make sure that there will be no future interpolation required when synchronized with another node
281  ros::Time stamp = image->header.stamp > depth->header.stamp? image->header.stamp : depth->header.stamp;
282  if(scanMsg.get() != 0)
283  {
284  if(stamp < scanMsg->header.stamp)
285  {
286  stamp = scanMsg->header.stamp;
287  }
288  }
289  else if(cloudMsg.get() != 0)
290  {
291  if(stamp < cloudMsg->header.stamp)
292  {
293  stamp = cloudMsg->header.stamp;
294  }
295  }
296 
297  Transform localTransform = rtabmap_conversions::getTransform(this->frameId(), image->header.frame_id, stamp, this->tfListener(), this->waitForTransformDuration());
298  if(localTransform.isNull())
299  {
300  return;
301  }
302 
303  double stampDiff = fabs(image->header.stamp.toSec() - depth->header.stamp.toSec());
304  if(stampDiff > 0.010)
305  {
306  NODELET_WARN("The time difference between rgb and depth frames is "
307  "high (diff=%fs, rgb=%fs, depth=%fs). You may want "
308  "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations or use "
309  "approx_sync=false if streams have all the exact same timestamp.",
310  stampDiff,
311  image->header.stamp.toSec(),
312  depth->header.stamp.toSec());
313  }
314 
315  if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
316  {
317  rtabmap::CameraModel rtabmapModel = rtabmap_conversions::cameraModelFromROS(*cameraInfo, localTransform);
319  image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1)==0 ||
320  image->encoding.compare(sensor_msgs::image_encodings::MONO8)==0?"":
321  keepColor_ && image->encoding.compare(sensor_msgs::image_encodings::MONO16)!=0?"bgr8":"mono8");
322  cv_bridge::CvImagePtr ptrDepth = cv_bridge::toCvCopy(depth);
323 
324  LaserScan scan;
325  Transform localScanTransform = Transform::getIdentity();
326  int maxLaserScans = 0;
327  if(scanMsg.get() != 0)
328  {
329  // make sure the frame of the laser is updated too
330  localScanTransform = rtabmap_conversions::getTransform(this->frameId(),
331  scanMsg->header.frame_id,
332  scanMsg->header.stamp + ros::Duration().fromSec(scanMsg->ranges.size()*scanMsg->time_increment),
333  this->tfListener(),
334  this->waitForTransformDuration());
335  if(localScanTransform.isNull())
336  {
337  ROS_ERROR("TF of received laser scan topic at time %fs is not set, aborting odometry update.", scanMsg->header.stamp.toSec());
338  return;
339  }
340 
341  //transform in frameId_ frame
342  sensor_msgs::PointCloud2 scanOut;
344  projection.transformLaserScanToPointCloud(scanMsg->header.frame_id, *scanMsg, scanOut, this->tfListener());
345  pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(new pcl::PointCloud<pcl::PointXYZ>);
346  pcl::fromROSMsg(scanOut, *pclScan);
347  pclScan->is_dense = true;
348 
349  maxLaserScans = (int)scanMsg->ranges.size();
350  if(pclScan->size())
351  {
352  if(scanVoxelSize_ > 0.0f)
353  {
354  float pointsBeforeFiltering = (float)pclScan->size();
355  pclScan = util3d::voxelize(pclScan, scanVoxelSize_);
356  float ratio = float(pclScan->size()) / pointsBeforeFiltering;
357  maxLaserScans = int(float(maxLaserScans) * ratio);
358  }
359  if(scanNormalK_ > 0 || scanNormalRadius_>0.0f)
360  {
361  //compute normals
362  pcl::PointCloud<pcl::Normal>::Ptr normals;
363  if(scanVoxelSize_ > 0.0f)
364  {
365  normals = util3d::computeNormals2D(pclScan, scanNormalK_, scanNormalRadius_);
366  }
367  else
368  {
369  normals = util3d::computeFastOrganizedNormals2D(pclScan, scanNormalK_, scanNormalRadius_);
370  }
371  pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(new pcl::PointCloud<pcl::PointNormal>);
372  pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
373  scan = util3d::laserScan2dFromPointCloud(*pclScanNormal);
374  }
375  else
376  {
377  scan = util3d::laserScan2dFromPointCloud(*pclScan);
378  }
379  }
380  }
381  else if(cloudMsg.get() != 0)
382  {
383  UASSERT_MSG(cloudMsg->data.size() == cloudMsg->row_step*cloudMsg->height,
384  uFormat("data=%d row_step=%d height=%d", cloudMsg->data.size(), cloudMsg->row_step, cloudMsg->height).c_str());
385 
386 
387  bool containNormals = false;
388  if(scanVoxelSize_ == 0.0f)
389  {
390  for(unsigned int i=0; i<cloudMsg->fields.size(); ++i)
391  {
392  if(cloudMsg->fields[i].name.compare("normal_x") == 0)
393  {
394  containNormals = true;
395  break;
396  }
397  }
398  }
399  localScanTransform = rtabmap_conversions::getTransform(this->frameId(), cloudMsg->header.frame_id, cloudMsg->header.stamp, this->tfListener(), this->waitForTransformDuration());
400  if(localScanTransform.isNull())
401  {
402  ROS_ERROR("TF of received scan cloud at time %fs is not set, aborting rtabmap update.", cloudMsg->header.stamp.toSec());
403  return;
404  }
405 
406  maxLaserScans = scanCloudMaxPoints_;
407  if(containNormals)
408  {
409  pcl::PointCloud<pcl::PointNormal>::Ptr pclScan(new pcl::PointCloud<pcl::PointNormal>);
410  pcl::fromROSMsg(*cloudMsg, *pclScan);
411  if(!pclScan->is_dense)
412  {
413  pclScan = util3d::removeNaNNormalsFromPointCloud(pclScan);
414  }
415  scan = util3d::laserScanFromPointCloud(*pclScan);
416  }
417  else
418  {
419  pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(new pcl::PointCloud<pcl::PointXYZ>);
420  pcl::fromROSMsg(*cloudMsg, *pclScan);
421  if(!pclScan->is_dense)
422  {
423  pclScan = util3d::removeNaNFromPointCloud(pclScan);
424  }
425 
426  if(pclScan->size())
427  {
428  if(scanVoxelSize_ > 0.0f)
429  {
430  float pointsBeforeFiltering = (float)pclScan->size();
431  pclScan = util3d::voxelize(pclScan, scanVoxelSize_);
432  float ratio = float(pclScan->size()) / pointsBeforeFiltering;
433  maxLaserScans = int(float(maxLaserScans) * ratio);
434  }
435  if(scanNormalK_ > 0 || scanNormalRadius_>0.0f)
436  {
437  //compute normals
438  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(pclScan, scanNormalK_, scanNormalRadius_);
439  pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(new pcl::PointCloud<pcl::PointNormal>);
440  pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
441  scan = util3d::laserScanFromPointCloud(*pclScanNormal);
442  }
443  else
444  {
445  scan = util3d::laserScanFromPointCloud(*pclScan);
446  }
447  }
448  }
449  }
450 
452  LaserScan(scan,
453  scanMsg.get() != 0 || cloudMsg.get() != 0?maxLaserScans:0,
454  scanMsg.get() != 0?scanMsg->range_max:0,
455  localScanTransform),
456  ptrImage->image,
457  ptrDepth->image,
458  rtabmapModel,
459  0,
461 
462  std_msgs::Header header;
463  header.stamp = stamp;
464  header.frame_id = image->header.frame_id;
465  this->processData(data, header);
466  }
467  }
468  }
469 
470 protected:
471  virtual void flushCallbacks()
472  {
473  // flush callbacks
474  if(approxScanSync_)
475  {
476  delete approxScanSync_;
477  approxScanSync_ = new message_filters::Synchronizer<MyApproxScanSyncPolicy>(MyApproxScanSyncPolicy(syncQueueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
478  approxScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
479  }
480  if(exactScanSync_)
481  {
482  delete exactScanSync_;
483  exactScanSync_ = new message_filters::Synchronizer<MyExactScanSyncPolicy>(MyExactScanSyncPolicy(syncQueueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
484  exactScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
485  }
486  if(approxCloudSync_)
487  {
488  delete approxCloudSync_;
489  approxCloudSync_ = new message_filters::Synchronizer<MyApproxCloudSyncPolicy>(MyApproxCloudSyncPolicy(syncQueueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
490  approxCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
491  }
492  if(exactCloudSync_)
493  {
494  delete exactCloudSync_;
495  exactCloudSync_ = new message_filters::Synchronizer<MyExactCloudSyncPolicy>(MyExactCloudSyncPolicy(syncQueueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
496  exactCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
497  }
498  }
499 
500 private:
521 };
522 
524 
525 }
rtabmap::SensorData
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
int
int
rtabmap_odom::RGBDICPOdometry::scanNormalRadius_
double scanNormalRadius_
Definition: rgbdicp_odometry.cpp:520
rtabmap_odom
Definition: OdometryROS.h:57
image_transport::SubscriberFilter
rtabmap_odom::RGBDICPOdometry::callbackCommon
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)
Definition: rgbdicp_odometry.cpp:253
rtabmap_odom::RGBDICPOdometry::onOdomInit
virtual void onOdomInit()
Definition: rgbdicp_odometry.cpp:107
sensor_msgs::image_encodings::TYPE_8UC1
const std::string TYPE_8UC1
NODELET_ERROR
#define NODELET_ERROR(...)
rtabmap_odom::RGBDICPOdometry::flushCallbacks
virtual void flushCallbacks()
Definition: rgbdicp_odometry.cpp:471
rtabmap_odom::RGBDICPOdometry::syncQueueSize_
int syncQueueSize_
Definition: rgbdicp_odometry.cpp:515
DurationBase< Duration >::fromSec
Duration & fromSec(double t)
image_encodings.h
image_transport::ImageTransport
message_filters::Synchronizer
boost::shared_ptr
rtabmap_conversions::getTransform
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
rtabmap_odom::RGBDICPOdometry::updateParameters
virtual void updateParameters(ParametersMap &parameters)
Definition: rgbdicp_odometry.cpp:222
rtabmap::util3d::removeNaNNormalsFromPointCloud
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
laser_geometry::LaserProjection
uFormat
std::string uFormat(const char *fmt,...)
rtabmap::Transform::getIdentity
static Transform getIdentity()
this
this
rtabmap::CameraModel
rtabmap_odom::RGBDICPOdometry::RGBDICPOdometry
RGBDICPOdometry()
Definition: rgbdicp_odometry.cpp:69
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
projection
Expression< Point2 > projection(f, p_cam)
rtabmap_odom::RGBDICPOdometry::callbackCloud
void callbackCloud(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
Definition: rgbdicp_odometry.cpp:243
sensor_msgs::image_encodings::RGBA8
const std::string RGBA8
frameId
string frameId
rtabmap_conversions::cameraModelFromROS
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
ros::TransportHints
UStl.h
NODELET_WARN
#define NODELET_WARN(...)
time_synchronizer.h
true
#define true
rtabmap_odom::RGBDICPOdometry::scanVoxelSize_
double scanVoxelSize_
Definition: rgbdicp_odometry.cpp:518
rtabmap::LaserScan
sensor_msgs::image_encodings::RGB8
const std::string RGB8
ParametersMap
std::map< std::string, std::string > ParametersMap
rtabmap_odom::RGBDICPOdometry::exactScanSync_
message_filters::Synchronizer< MyExactScanSyncPolicy > * exactScanSync_
Definition: rgbdicp_odometry.cpp:509
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
f
Vector3 f(-6, 1, 0.5)
rtabmap::Transform::isNull
bool isNull() const
stereo_camera_model.h
data
data
fabs
Real fabs(const Real &a)
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
message_filters::Subscriber< sensor_msgs::CameraInfo >
rtabmap_odom::RGBDICPOdometry::scanCloudMaxPoints_
int scanCloudMaxPoints_
Definition: rgbdicp_odometry.cpp:517
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
rtabmap_odom::RGBDICPOdometry::image_mono_sub_
image_transport::SubscriberFilter image_mono_sub_
Definition: rgbdicp_odometry.cpp:501
laser_geometry.h
rtabmap_odom::RGBDICPOdometry::approxCloudSync_
message_filters::Synchronizer< MyApproxCloudSyncPolicy > * approxCloudSync_
Definition: rgbdicp_odometry.cpp:511
message_filters::sync_policies::ApproximateTime
rtabmap_odom::RGBDICPOdometry::cloud_sub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloud_sub_
Definition: rgbdicp_odometry.cpp:505
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)
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
rtabmap_odom::RGBDICPOdometry::MyExactCloudSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > MyExactCloudSyncPolicy
Definition: rgbdicp_odometry.cpp:512
rtabmap_odom::RGBDICPOdometry::queueSize_
int queueSize_
Definition: rgbdicp_odometry.cpp:514
subscriber.h
rtabmap::util3d::laserScanFromPointCloud
LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud< pcl::PointNormal > &cloud, const pcl::IndicesPtr &indices, const Transform &transform=Transform(), bool filterNaNs=true)
rtabmap_odom::RGBDICPOdometry::MyApproxScanSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > MyApproxScanSyncPolicy
Definition: rgbdicp_odometry.cpp:506
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
ROS_WARN
#define ROS_WARN(...)
rtabmap_odom::RGBDICPOdometry::scanNormalK_
int scanNormalK_
Definition: rgbdicp_odometry.cpp:519
rtabmap_odom::RGBDICPOdometry
Definition: rgbdicp_odometry.cpp:66
rtabmap::util3d::computeNormals2D
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT computeNormals2D(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
UASSERT_MSG
#define UASSERT_MSG(condition, msg_str)
image_transport.h
util3d_filtering.h
rtabmap_odom::OdometryROS
Definition: OdometryROS.h:59
NODELET_INFO
#define NODELET_INFO(...)
rtabmap_odom::RGBDICPOdometry::~RGBDICPOdometry
virtual ~RGBDICPOdometry()
Definition: rgbdicp_odometry.cpp:85
rtabmap::Transform
rtabmap_odom::RGBDICPOdometry::MyExactScanSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > MyExactScanSyncPolicy
Definition: rgbdicp_odometry.cpp:508
rtabmap_conversions::timestampFromROS
double timestampFromROS(const ros::Time &stamp)
nodelet::Nodelet
rtabmap_odom::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_odom::RGBDICPOdometry, nodelet::Nodelet)
ros::Time
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_odom::RGBDICPOdometry::keepColor_
bool keepColor_
Definition: rgbdicp_odometry.cpp:516
nodelet.h
sensor_msgs::image_encodings::MONO8
const std::string MONO8
c_str
const char * c_str(Args &&...args)
ratio
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size ratio
cv_bridge.h
sensor_msgs::image_encodings::MONO16
const std::string MONO16
ROS_ERROR
#define ROS_ERROR(...)
rtabmap_odom::RGBDICPOdometry::exactCloudSync_
message_filters::Synchronizer< MyExactCloudSyncPolicy > * exactCloudSync_
Definition: rgbdicp_odometry.cpp:513
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
float
float
ULogger.h
approximate_time.h
rtabmap_odom::RGBDICPOdometry::info_sub_
message_filters::Subscriber< sensor_msgs::CameraInfo > info_sub_
Definition: rgbdicp_odometry.cpp:503
rtabmap::util3d::laserScan2dFromPointCloud
LaserScan RTABMAP_CORE_EXPORT laserScan2dFromPointCloud(const pcl::PointCloud< pcl::PointNormal > &cloud, const Transform &transform=Transform(), bool filterNaNs=true)
sensor_msgs::image_encodings::BGR8
const std::string BGR8
sensor_msgs::image_encodings::BAYER_GRBG8
const std::string BAYER_GRBG8
false
#define false
rtabmap::util3d::computeNormals
cv::Mat RTABMAP_CORE_EXPORT computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
image_transport::TransportHints
util3d_surface.h
rtabmap_odom::RGBDICPOdometry::approxScanSync_
message_filters::Synchronizer< MyApproxScanSyncPolicy > * approxScanSync_
Definition: rgbdicp_odometry.cpp:507
header
const std::string header
UConversion.h
OdometryROS.h
MsgConversion.h
rtabmap
util3d_transforms.h
rtabmap::util3d::computeFastOrganizedNormals2D
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals2D(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
ros::Duration
rtabmap_odom::RGBDICPOdometry::scan_sub_
message_filters::Subscriber< sensor_msgs::LaserScan > scan_sub_
Definition: rgbdicp_odometry.cpp:504
i
int i
rtabmap_odom::RGBDICPOdometry::callbackScan
void callbackScan(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::LaserScanConstPtr &scanMsg)
Definition: rgbdicp_odometry.cpp:233
util3d.h
rtabmap_odom::RGBDICPOdometry::MyApproxCloudSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > MyApproxCloudSyncPolicy
Definition: rgbdicp_odometry.cpp:510
ros::NodeHandle
util2d.h
rtabmap_odom::RGBDICPOdometry::image_depth_sub_
image_transport::SubscriberFilter image_depth_sub_
Definition: rgbdicp_odometry.cpp:502
pcl_conversions.h


rtabmap_odom
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:42:24