43 #include <sensor_msgs/Image.h> 46 #include <sensor_msgs/LaserScan.h> 47 #include <sensor_msgs/PointCloud2.h> 77 scanCloudMaxPoints_(0),
80 scanNormalRadius_(0.0)
88 delete approxScanSync_;
92 delete exactScanSync_;
96 delete approxCloudSync_;
100 delete exactCloudSync_;
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_);
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_);
127 pnh.
param(
"scan_normal_radius", scanNormalRadius_, scanNormalRadius_);
128 pnh.
param(
"keep_color", keepColor_, keepColor_);
130 NODELET_INFO(
"RGBDIcpOdometry: approx_sync = %s", approxSync?
"true":
"false");
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");
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);
154 std::string subscribedTopicsMsg;
155 if(subscribeScanCloud)
157 cloud_sub_.subscribe(nh,
"scan_cloud", 1);
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));
168 exactCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
171 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync%s):\n %s,\n %s,\n %s, \n %s",
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());
182 scan_sub_.subscribe(nh,
"scan", 1);
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));
193 exactScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
196 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync%s):\n %s \\\n %s \\\n %s \\\n %s",
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());
205 this->startWarningThread(subscribedTopicsMsg, approxSync);
211 ParametersMap::iterator iter = parameters.find(Parameters::kRegStrategy());
212 if(iter != parameters.end() && iter->second.compare(
"0") != 0)
214 ROS_WARN(
"RGBDICP odometry works only with \"Reg/Strategy\"=2. Ignoring value %s.", iter->second.c_str());
220 const sensor_msgs::ImageConstPtr& image,
221 const sensor_msgs::ImageConstPtr& depth,
222 const sensor_msgs::CameraInfoConstPtr& cameraInfo,
223 const sensor_msgs::LaserScanConstPtr& scanMsg)
225 sensor_msgs::PointCloud2ConstPtr cloudMsg;
226 callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
230 const sensor_msgs::ImageConstPtr& image,
231 const sensor_msgs::ImageConstPtr& depth,
232 const sensor_msgs::CameraInfoConstPtr& cameraInfo,
233 const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
235 sensor_msgs::LaserScanConstPtr scanMsg;
236 callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
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)
247 if(!this->isPaused())
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());
268 ros::Time stamp = image->header.stamp > depth->header.stamp? image->header.stamp : depth->header.stamp;
269 if(scanMsg.get() != 0)
271 if(stamp < scanMsg->
header.stamp)
273 stamp = scanMsg->header.stamp;
276 else if(cloudMsg.get() != 0)
278 if(stamp < cloudMsg->
header.stamp)
280 stamp = cloudMsg->header.stamp;
284 Transform localTransform =
getTransform(this->
frameId(), image->header.frame_id, stamp, this->tfListener(), this->waitForTransformDuration());
285 if(localTransform.
isNull())
290 double stampDiff = fabs(image->header.stamp.toSec() - depth->header.stamp.toSec());
291 if(stampDiff > 0.010)
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.",
298 image->header.stamp.toSec(),
299 depth->header.stamp.toSec());
302 if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
313 int maxLaserScans = 0;
314 if(scanMsg.get() != 0)
318 scanMsg->header.frame_id,
319 scanMsg->header.stamp +
ros::Duration().
fromSec(scanMsg->ranges.size()*scanMsg->time_increment),
321 this->waitForTransformDuration());
322 if(localScanTransform.
isNull())
324 ROS_ERROR(
"TF of received laser scan topic at time %fs is not set, aborting odometry update.", scanMsg->header.stamp.toSec());
329 sensor_msgs::PointCloud2 scanOut;
332 pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(
new pcl::PointCloud<pcl::PointXYZ>);
334 pclScan->is_dense =
true;
336 maxLaserScans = (int)scanMsg->ranges.size();
339 if(scanVoxelSize_ > 0.0
f)
341 float pointsBeforeFiltering = (float)pclScan->size();
343 float ratio = float(pclScan->size()) / pointsBeforeFiltering;
344 maxLaserScans = int(
float(maxLaserScans) * ratio);
346 if(scanNormalK_ > 0 || scanNormalRadius_>0.0
f)
349 pcl::PointCloud<pcl::Normal>::Ptr normals;
350 if(scanVoxelSize_ > 0.0
f)
358 pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(
new pcl::PointCloud<pcl::PointNormal>);
359 pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
368 else if(cloudMsg.get() != 0)
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());
374 bool containNormals =
false;
375 if(scanVoxelSize_ == 0.0
f)
377 for(
unsigned int i=0; i<cloudMsg->fields.size(); ++i)
379 if(cloudMsg->fields[i].name.compare(
"normal_x") == 0)
381 containNormals =
true;
386 localScanTransform =
getTransform(this->
frameId(), cloudMsg->header.frame_id, cloudMsg->header.stamp, this->tfListener(), this->waitForTransformDuration());
387 if(localScanTransform.
isNull())
389 ROS_ERROR(
"TF of received scan cloud at time %fs is not set, aborting rtabmap update.", cloudMsg->header.stamp.toSec());
393 maxLaserScans = scanCloudMaxPoints_;
396 pcl::PointCloud<pcl::PointNormal>::Ptr pclScan(
new pcl::PointCloud<pcl::PointNormal>);
398 if(!pclScan->is_dense)
406 pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(
new pcl::PointCloud<pcl::PointXYZ>);
408 if(!pclScan->is_dense)
415 if(scanVoxelSize_ > 0.0
f)
417 float pointsBeforeFiltering = (float)pclScan->size();
419 float ratio = float(pclScan->size()) / pointsBeforeFiltering;
420 maxLaserScans = int(
float(maxLaserScans) * ratio);
422 if(scanNormalK_ > 0 || scanNormalRadius_>0.0
f)
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);
440 scanMsg.get() != 0 || cloudMsg.get() != 0?maxLaserScans:0,
441 scanMsg.get() != 0?scanMsg->range_max:0,
450 header.stamp =
stamp;
451 header.frame_id = image->header.frame_id;
452 this->processData(
data, header);
463 delete approxScanSync_;
465 approxScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
469 delete exactScanSync_;
471 exactScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
475 delete approxCloudSync_;
477 approxCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
481 delete exactCloudSync_;
483 exactCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
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(...)
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
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_
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 ¶m_name, T ¶m_val, const T &default_val) const
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
virtual ~RGBDICPOdometry()
virtual void updateParameters(ParametersMap ¶meters)
bool hasParam(const std::string &key) const
#define NODELET_INFO(...)
virtual void onOdomInit()
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > MyApproxScanSyncPolicy
double timestampFromROS(const ros::Time &stamp)
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)
virtual void flushCallbacks()
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
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)