43 #include <sensor_msgs/Image.h>
46 #include <sensor_msgs/LaserScan.h>
47 #include <sensor_msgs/PointCloud2.h>
78 scanCloudMaxPoints_(0),
81 scanNormalRadius_(0.0)
89 delete approxScanSync_;
93 delete exactScanSync_;
97 delete approxCloudSync_;
101 delete exactCloudSync_;
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_);
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_);
128 pnh.
param(
"sync_queue_size", syncQueueSize_, syncQueueSize_);
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_);
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_);
140 pnh.
param(
"scan_normal_radius", scanNormalRadius_, scanNormalRadius_);
141 pnh.
param(
"keep_color", keepColor_, keepColor_);
143 NODELET_INFO(
"RGBDIcpOdometry: approx_sync = %s", approxSync?
"true":
"false");
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");
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_);
168 std::string subscribedTopicsMsg;
169 if(subscribeScanCloud)
171 cloud_sub_.subscribe(nh,
"scan_cloud", queueSize_);
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));
182 exactCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
185 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync%s):\n %s,\n %s,\n %s, \n %s",
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());
196 scan_sub_.subscribe(nh,
"scan", queueSize_);
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));
207 exactScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
210 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s \\\n %s",
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());
219 initDiagnosticMsg(subscribedTopicsMsg, approxSync);
225 ParametersMap::iterator
iter = parameters.find(Parameters::kRegStrategy());
226 if(
iter != parameters.end() &&
iter->second.compare(
"2") != 0)
228 ROS_WARN(
"RGBDICP odometry works only with \"Reg/Strategy\"=2. Ignoring value %s.",
iter->second.c_str());
234 const sensor_msgs::ImageConstPtr& image,
235 const sensor_msgs::ImageConstPtr& depth,
236 const sensor_msgs::CameraInfoConstPtr& cameraInfo,
237 const sensor_msgs::LaserScanConstPtr& scanMsg)
239 sensor_msgs::PointCloud2ConstPtr cloudMsg;
240 callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
244 const sensor_msgs::ImageConstPtr& image,
245 const sensor_msgs::ImageConstPtr& depth,
246 const sensor_msgs::CameraInfoConstPtr& cameraInfo,
247 const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
249 sensor_msgs::LaserScanConstPtr scanMsg;
250 callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
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)
260 if(!this->isPaused())
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());
281 ros::Time stamp = image->header.stamp > depth->header.stamp? image->header.stamp : depth->header.stamp;
282 if(scanMsg.get() != 0)
284 if(stamp < scanMsg->
header.stamp)
286 stamp = scanMsg->header.stamp;
289 else if(cloudMsg.get() != 0)
291 if(stamp < cloudMsg->
header.stamp)
293 stamp = cloudMsg->header.stamp;
298 if(localTransform.
isNull())
303 double stampDiff =
fabs(image->header.stamp.toSec() - depth->header.stamp.toSec());
304 if(stampDiff > 0.010)
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.",
311 image->header.stamp.toSec(),
312 depth->header.stamp.toSec());
315 if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
326 int maxLaserScans = 0;
327 if(scanMsg.get() != 0)
331 scanMsg->header.frame_id,
332 scanMsg->header.stamp +
ros::Duration().
fromSec(scanMsg->ranges.size()*scanMsg->time_increment),
334 this->waitForTransformDuration());
335 if(localScanTransform.
isNull())
337 ROS_ERROR(
"TF of received laser scan topic at time %fs is not set, aborting odometry update.", scanMsg->header.stamp.toSec());
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>);
347 pclScan->is_dense =
true;
349 maxLaserScans = (
int)scanMsg->ranges.size();
352 if(scanVoxelSize_ > 0.0
f)
354 float pointsBeforeFiltering = (
float)pclScan->size();
356 float ratio =
float(pclScan->size()) / pointsBeforeFiltering;
357 maxLaserScans =
int(
float(maxLaserScans) *
ratio);
359 if(scanNormalK_ > 0 || scanNormalRadius_>0.0
f)
362 pcl::PointCloud<pcl::Normal>::Ptr normals;
363 if(scanVoxelSize_ > 0.0
f)
371 pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(
new pcl::PointCloud<pcl::PointNormal>);
372 pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
381 else if(cloudMsg.get() != 0)
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());
387 bool containNormals =
false;
388 if(scanVoxelSize_ == 0.0
f)
390 for(
unsigned int i=0;
i<cloudMsg->fields.size(); ++
i)
392 if(cloudMsg->fields[
i].name.compare(
"normal_x") == 0)
394 containNormals =
true;
400 if(localScanTransform.
isNull())
402 ROS_ERROR(
"TF of received scan cloud at time %fs is not set, aborting rtabmap update.", cloudMsg->header.stamp.toSec());
406 maxLaserScans = scanCloudMaxPoints_;
409 pcl::PointCloud<pcl::PointNormal>::Ptr pclScan(
new pcl::PointCloud<pcl::PointNormal>);
411 if(!pclScan->is_dense)
419 pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(
new pcl::PointCloud<pcl::PointXYZ>);
421 if(!pclScan->is_dense)
428 if(scanVoxelSize_ > 0.0
f)
430 float pointsBeforeFiltering = (
float)pclScan->size();
432 float ratio =
float(pclScan->size()) / pointsBeforeFiltering;
433 maxLaserScans =
int(
float(maxLaserScans) *
ratio);
435 if(scanNormalK_ > 0 || scanNormalRadius_>0.0
f)
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);
453 scanMsg.get() != 0 || cloudMsg.get() != 0?maxLaserScans:0,
454 scanMsg.get() != 0?scanMsg->range_max:0,
464 header.frame_id = image->header.frame_id;
476 delete approxScanSync_;
478 approxScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
482 delete exactScanSync_;
484 exactScanSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
488 delete approxCloudSync_;
490 approxCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
494 delete exactCloudSync_;
496 exactCloudSync_->registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));