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  keepColor_(false),
77  scanCloudMaxPoints_(0),
78  scanVoxelSize_(0.0),
79  scanNormalK_(0),
80  scanNormalRadius_(0.0)
81  {
82  }
83 
84  virtual ~RGBDICPOdometry()
85  {
86  if(approxScanSync_)
87  {
88  delete approxScanSync_;
89  }
90  if(exactScanSync_)
91  {
92  delete exactScanSync_;
93  }
94  if(approxCloudSync_)
95  {
96  delete approxCloudSync_;
97  }
98  if(exactCloudSync_)
99  {
100  delete exactCloudSync_;
101  }
102  }
103 
104 private:
105 
106  virtual void onOdomInit()
107  {
108  ros::NodeHandle & nh = getNodeHandle();
109  ros::NodeHandle & pnh = getPrivateNodeHandle();
110 
111  bool approxSync = true;
112  bool subscribeScanCloud = false;
113  double approxSyncMaxInterval = 0.0;
114  pnh.param("approx_sync", approxSync, approxSync);
115  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
116  pnh.param("queue_size", queueSize_, queueSize_);
117  pnh.param("subscribe_scan_cloud", subscribeScanCloud, subscribeScanCloud);
118  pnh.param("scan_cloud_max_points", scanCloudMaxPoints_, scanCloudMaxPoints_);
119  pnh.param("scan_voxel_size", scanVoxelSize_, scanVoxelSize_);
120  pnh.param("scan_normal_k", scanNormalK_, scanNormalK_);
121  if(pnh.hasParam("scan_cloud_normal_k") && !pnh.hasParam("scan_normal_k"))
122  {
123  ROS_WARN("rtabmap: Parameter \"scan_cloud_normal_k\" has been renamed to \"scan_normal_k\". "
124  "The value is still used. Use \"scan_normal_k\" to avoid this warning.");
125  pnh.param("scan_cloud_normal_k", scanNormalK_, scanNormalK_);
126  }
127  pnh.param("scan_normal_radius", scanNormalRadius_, scanNormalRadius_);
128  pnh.param("keep_color", keepColor_, keepColor_);
129 
130  NODELET_INFO("RGBDIcpOdometry: approx_sync = %s", approxSync?"true":"false");
131  if(approxSync)
132  NODELET_INFO("RGBDIcpOdometry: approx_sync_max_interval = %f", approxSyncMaxInterval);
133  NODELET_INFO("RGBDIcpOdometry: queue_size = %d", queueSize_);
134  NODELET_INFO("RGBDIcpOdometry: subscribe_scan_cloud = %s", subscribeScanCloud?"true":"false");
135  NODELET_INFO("RGBDIcpOdometry: scan_cloud_max_points = %d", scanCloudMaxPoints_);
136  NODELET_INFO("RGBDIcpOdometry: scan_voxel_size = %f", scanVoxelSize_);
137  NODELET_INFO("RGBDIcpOdometry: scan_normal_k = %d", scanNormalK_);
138  NODELET_INFO("RGBDIcpOdometry: scan_normal_radius = %f", scanNormalRadius_);
139  NODELET_INFO("RGBDIcpOdometry: keep_color = %s", keepColor_?"true":"false");
140 
141  ros::NodeHandle rgb_nh(nh, "rgb");
142  ros::NodeHandle depth_nh(nh, "depth");
143  ros::NodeHandle rgb_pnh(pnh, "rgb");
144  ros::NodeHandle depth_pnh(pnh, "depth");
145  image_transport::ImageTransport rgb_it(rgb_nh);
146  image_transport::ImageTransport depth_it(depth_nh);
147  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
148  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
149 
150  image_mono_sub_.subscribe(rgb_it, rgb_nh.resolveName("image"), 1, hintsRgb);
151  image_depth_sub_.subscribe(depth_it, depth_nh.resolveName("image"), 1, hintsDepth);
152  info_sub_.subscribe(rgb_nh, "camera_info", 1);
153 
154  std::string subscribedTopicsMsg;
155  if(subscribeScanCloud)
156  {
157  cloud_sub_.subscribe(nh, "scan_cloud", 1);
158  if(approxSync)
159  {
160  approxCloudSync_ = new message_filters::Synchronizer<MyApproxCloudSyncPolicy>(MyApproxCloudSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
161  if(approxSyncMaxInterval > 0.0)
162  approxCloudSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
163  approxCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
164  }
165  else
166  {
167  exactCloudSync_ = new message_filters::Synchronizer<MyExactCloudSyncPolicy>(MyExactCloudSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
168  exactCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
169  }
170 
171  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync%s):\n %s,\n %s,\n %s, \n %s",
172  getName().c_str(),
173  approxSync?"approx":"exact",
174  approxSync&&approxSyncMaxInterval!=0.0?uFormat(", max interval=%fs", approxSyncMaxInterval).c_str():"",
175  image_mono_sub_.getTopic().c_str(),
176  image_depth_sub_.getTopic().c_str(),
177  info_sub_.getTopic().c_str(),
178  cloud_sub_.getTopic().c_str());
179  }
180  else
181  {
182  scan_sub_.subscribe(nh, "scan", 1);
183  if(approxSync)
184  {
185  approxScanSync_ = new message_filters::Synchronizer<MyApproxScanSyncPolicy>(MyApproxScanSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
186  if(approxSyncMaxInterval > 0.0)
187  approxScanSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
188  approxScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
189  }
190  else
191  {
192  exactScanSync_ = new message_filters::Synchronizer<MyExactScanSyncPolicy>(MyExactScanSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
193  exactScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
194  }
195 
196  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s \\\n %s",
197  getName().c_str(),
198  approxSync?"approx":"exact",
199  approxSync&&approxSyncMaxInterval!=0.0?uFormat(", max interval=%fs", approxSyncMaxInterval).c_str():"",
200  image_mono_sub_.getTopic().c_str(),
201  image_depth_sub_.getTopic().c_str(),
202  info_sub_.getTopic().c_str(),
203  scan_sub_.getTopic().c_str());
204  }
205  this->startWarningThread(subscribedTopicsMsg, approxSync);
206  }
207 
208  virtual void updateParameters(ParametersMap & parameters)
209  {
210  //make sure we are using Reg/Strategy=0
211  ParametersMap::iterator iter = parameters.find(Parameters::kRegStrategy());
212  if(iter != parameters.end() && iter->second.compare("0") != 0)
213  {
214  ROS_WARN("RGBDICP odometry works only with \"Reg/Strategy\"=2. Ignoring value %s.", iter->second.c_str());
215  }
216  uInsert(parameters, ParametersPair(Parameters::kRegStrategy(), "2"));
217  }
218 
220  const sensor_msgs::ImageConstPtr& image,
221  const sensor_msgs::ImageConstPtr& depth,
222  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
223  const sensor_msgs::LaserScanConstPtr& scanMsg)
224  {
225  sensor_msgs::PointCloud2ConstPtr cloudMsg;
226  callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
227  }
228 
230  const sensor_msgs::ImageConstPtr& image,
231  const sensor_msgs::ImageConstPtr& depth,
232  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
233  const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
234  {
235  sensor_msgs::LaserScanConstPtr scanMsg;
236  callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
237  }
238 
240  const sensor_msgs::ImageConstPtr& image,
241  const sensor_msgs::ImageConstPtr& depth,
242  const sensor_msgs::CameraInfoConstPtr& cameraInfo,
243  const sensor_msgs::LaserScanConstPtr& scanMsg,
244  const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
245  {
246  callbackCalled();
247  if(!this->isPaused())
248  {
249  if(!(image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1) ==0 ||
250  image->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
251  image->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
252  image->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
253  image->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0 ||
254  image->encoding.compare(sensor_msgs::image_encodings::BGRA8) == 0 ||
255  image->encoding.compare(sensor_msgs::image_encodings::RGBA8) == 0 ||
256  image->encoding.compare(sensor_msgs::image_encodings::BAYER_GRBG8) == 0) ||
257  !(depth->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)==0 ||
258  depth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0 ||
259  depth->encoding.compare(sensor_msgs::image_encodings::MONO16)==0))
260  {
261  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8,rgba8,bgra8 (mono8 "
262  "recommended) and image_depth=16UC1,32FC1,mono16. Types detected: %s %s",
263  image->encoding.c_str(), depth->encoding.c_str());
264  return;
265  }
266 
267  // use the highest stamp to make sure that there will be no future interpolation required when synchronized with another node
268  ros::Time stamp = image->header.stamp > depth->header.stamp? image->header.stamp : depth->header.stamp;
269  if(scanMsg.get() != 0)
270  {
271  if(stamp < scanMsg->header.stamp)
272  {
273  stamp = scanMsg->header.stamp;
274  }
275  }
276  else if(cloudMsg.get() != 0)
277  {
278  if(stamp < cloudMsg->header.stamp)
279  {
280  stamp = cloudMsg->header.stamp;
281  }
282  }
283 
284  Transform localTransform = getTransform(this->frameId(), image->header.frame_id, stamp, this->tfListener(), this->waitForTransformDuration());
285  if(localTransform.isNull())
286  {
287  return;
288  }
289 
290  double stampDiff = fabs(image->header.stamp.toSec() - depth->header.stamp.toSec());
291  if(stampDiff > 0.010)
292  {
293  NODELET_WARN("The time difference between rgb and depth frames is "
294  "high (diff=%fs, rgb=%fs, depth=%fs). You may want "
295  "to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations or use "
296  "approx_sync=false if streams have all the exact same timestamp.",
297  stampDiff,
298  image->header.stamp.toSec(),
299  depth->header.stamp.toSec());
300  }
301 
302  if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
303  {
304  rtabmap::CameraModel rtabmapModel = rtabmap_ros::cameraModelFromROS(*cameraInfo, localTransform);
306  image->encoding.compare(sensor_msgs::image_encodings::TYPE_8UC1)==0 ||
307  image->encoding.compare(sensor_msgs::image_encodings::MONO8)==0?"":
308  keepColor_ && image->encoding.compare(sensor_msgs::image_encodings::MONO16)!=0?"bgr8":"mono8");
309  cv_bridge::CvImagePtr ptrDepth = cv_bridge::toCvCopy(depth);
310 
311  LaserScan scan;
312  Transform localScanTransform = Transform::getIdentity();
313  int maxLaserScans = 0;
314  if(scanMsg.get() != 0)
315  {
316  // make sure the frame of the laser is updated too
317  localScanTransform = getTransform(this->frameId(),
318  scanMsg->header.frame_id,
319  scanMsg->header.stamp + ros::Duration().fromSec(scanMsg->ranges.size()*scanMsg->time_increment),
320  this->tfListener(),
321  this->waitForTransformDuration());
322  if(localScanTransform.isNull())
323  {
324  ROS_ERROR("TF of received laser scan topic at time %fs is not set, aborting odometry update.", scanMsg->header.stamp.toSec());
325  return;
326  }
327 
328  //transform in frameId_ frame
329  sensor_msgs::PointCloud2 scanOut;
331  projection.transformLaserScanToPointCloud(scanMsg->header.frame_id, *scanMsg, scanOut, this->tfListener());
332  pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(new pcl::PointCloud<pcl::PointXYZ>);
333  pcl::fromROSMsg(scanOut, *pclScan);
334  pclScan->is_dense = true;
335 
336  maxLaserScans = (int)scanMsg->ranges.size();
337  if(pclScan->size())
338  {
339  if(scanVoxelSize_ > 0.0f)
340  {
341  float pointsBeforeFiltering = (float)pclScan->size();
342  pclScan = util3d::voxelize(pclScan, scanVoxelSize_);
343  float ratio = float(pclScan->size()) / pointsBeforeFiltering;
344  maxLaserScans = int(float(maxLaserScans) * ratio);
345  }
346  if(scanNormalK_ > 0 || scanNormalRadius_>0.0f)
347  {
348  //compute normals
349  pcl::PointCloud<pcl::Normal>::Ptr normals;
350  if(scanVoxelSize_ > 0.0f)
351  {
352  normals = util3d::computeNormals2D(pclScan, scanNormalK_, scanNormalRadius_);
353  }
354  else
355  {
356  normals = util3d::computeFastOrganizedNormals2D(pclScan, scanNormalK_, scanNormalRadius_);
357  }
358  pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(new pcl::PointCloud<pcl::PointNormal>);
359  pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
360  scan = util3d::laserScan2dFromPointCloud(*pclScanNormal);
361  }
362  else
363  {
364  scan = util3d::laserScan2dFromPointCloud(*pclScan);
365  }
366  }
367  }
368  else if(cloudMsg.get() != 0)
369  {
370  UASSERT_MSG(cloudMsg->data.size() == cloudMsg->row_step*cloudMsg->height,
371  uFormat("data=%d row_step=%d height=%d", cloudMsg->data.size(), cloudMsg->row_step, cloudMsg->height).c_str());
372 
373 
374  bool containNormals = false;
375  if(scanVoxelSize_ == 0.0f)
376  {
377  for(unsigned int i=0; i<cloudMsg->fields.size(); ++i)
378  {
379  if(cloudMsg->fields[i].name.compare("normal_x") == 0)
380  {
381  containNormals = true;
382  break;
383  }
384  }
385  }
386  localScanTransform = getTransform(this->frameId(), cloudMsg->header.frame_id, cloudMsg->header.stamp, this->tfListener(), this->waitForTransformDuration());
387  if(localScanTransform.isNull())
388  {
389  ROS_ERROR("TF of received scan cloud at time %fs is not set, aborting rtabmap update.", cloudMsg->header.stamp.toSec());
390  return;
391  }
392 
393  maxLaserScans = scanCloudMaxPoints_;
394  if(containNormals)
395  {
396  pcl::PointCloud<pcl::PointNormal>::Ptr pclScan(new pcl::PointCloud<pcl::PointNormal>);
397  pcl::fromROSMsg(*cloudMsg, *pclScan);
398  if(!pclScan->is_dense)
399  {
400  pclScan = util3d::removeNaNNormalsFromPointCloud(pclScan);
401  }
402  scan = util3d::laserScanFromPointCloud(*pclScan);
403  }
404  else
405  {
406  pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(new pcl::PointCloud<pcl::PointXYZ>);
407  pcl::fromROSMsg(*cloudMsg, *pclScan);
408  if(!pclScan->is_dense)
409  {
410  pclScan = util3d::removeNaNFromPointCloud(pclScan);
411  }
412 
413  if(pclScan->size())
414  {
415  if(scanVoxelSize_ > 0.0f)
416  {
417  float pointsBeforeFiltering = (float)pclScan->size();
418  pclScan = util3d::voxelize(pclScan, scanVoxelSize_);
419  float ratio = float(pclScan->size()) / pointsBeforeFiltering;
420  maxLaserScans = int(float(maxLaserScans) * ratio);
421  }
422  if(scanNormalK_ > 0 || scanNormalRadius_>0.0f)
423  {
424  //compute normals
425  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(pclScan, scanNormalK_, scanNormalRadius_);
426  pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(new pcl::PointCloud<pcl::PointNormal>);
427  pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
428  scan = util3d::laserScanFromPointCloud(*pclScanNormal);
429  }
430  else
431  {
432  scan = util3d::laserScanFromPointCloud(*pclScan);
433  }
434  }
435  }
436  }
437 
439  LaserScan(scan,
440  scanMsg.get() != 0 || cloudMsg.get() != 0?maxLaserScans:0,
441  scanMsg.get() != 0?scanMsg->range_max:0,
442  localScanTransform),
443  ptrImage->image,
444  ptrDepth->image,
445  rtabmapModel,
446  0,
448 
449  std_msgs::Header header;
450  header.stamp = stamp;
451  header.frame_id = image->header.frame_id;
452  this->processData(data, header);
453  }
454  }
455  }
456 
457 protected:
458  virtual void flushCallbacks()
459  {
460  // flush callbacks
461  if(approxScanSync_)
462  {
463  delete approxScanSync_;
464  approxScanSync_ = new message_filters::Synchronizer<MyApproxScanSyncPolicy>(MyApproxScanSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
465  approxScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
466  }
467  if(exactScanSync_)
468  {
469  delete exactScanSync_;
470  exactScanSync_ = new message_filters::Synchronizer<MyExactScanSyncPolicy>(MyExactScanSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, scan_sub_);
471  exactScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
472  }
473  if(approxCloudSync_)
474  {
475  delete approxCloudSync_;
476  approxCloudSync_ = new message_filters::Synchronizer<MyApproxCloudSyncPolicy>(MyApproxCloudSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
477  approxCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
478  }
479  if(exactCloudSync_)
480  {
481  delete exactCloudSync_;
482  exactCloudSync_ = new message_filters::Synchronizer<MyExactCloudSyncPolicy>(MyExactCloudSyncPolicy(queueSize_), image_mono_sub_, image_depth_sub_, info_sub_, cloud_sub_);
483  exactCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
484  }
485  }
486 
487 private:
507 };
508 
510 
511 }
const std::string BAYER_GRBG8
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))
#define NODELET_WARN(...)
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
static Transform getIdentity()
data
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_
ROSCONSOLE_CONSOLE_IMPL_DECL 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))
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)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define true
Connection registerCallback(C &callback)
message_filters::Synchronizer< MyExactScanSyncPolicy > * exactScanSync_
message_filters::Synchronizer< MyApproxCloudSyncPolicy > * approxCloudSync_
#define UASSERT_MSG(condition, msg_str)
Duration & fromSec(double t)
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)
std::string resolveName(const std::string &name, bool remap=true) const
LaserScan laserScanFromPointCloud(const PointCloud2T &cloud, bool filterNaNs, bool is2D, const Transform &transform)
QMap< QString, QVariant > ParametersMap
const std::string MONO16
virtual void updateParameters(ParametersMap &parameters)
bool hasParam(const std::string &key) const
bool isNull() const
string frameId
Definition: patrol.py:11
#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)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
#define ROS_ERROR(...)
PLUGINLIB_EXPORT_CLASS(apriltag_ros::ContinuousDetector, nodelet::Nodelet)
LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud, const Transform &transform=Transform(), bool filterNaNs=true)
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)


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