43 #include <sensor_msgs/Image.h> 46 #include <sensor_msgs/LaserScan.h> 47 #include <sensor_msgs/PointCloud2.h> 76 scanCloudMaxPoints_(0),
79 scanNormalRadius_(0.0)
87 delete approxScanSync_;
91 delete exactScanSync_;
95 delete approxCloudSync_;
99 delete exactCloudSync_;
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_);
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_);
124 pnh.
param(
"scan_normal_radius", scanNormalRadius_, scanNormalRadius_);
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_);
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);
147 std::string subscribedTopicsMsg;
148 if(subscribeScanCloud)
150 cloud_sub_.subscribe(nh,
"scan_cloud", 1);
154 approxCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, _1, _2, _3, _4));
159 exactCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, _1, _2, _3, _4));
162 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync):\n %s,\n %s,\n %s, \n %s",
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());
172 scan_sub_.subscribe(nh,
"scan", 1);
176 approxScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, _1, _2, _3, _4));
181 exactScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, _1, _2, _3, _4));
184 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync):\n %s,\n %s,\n %s, \n %s",
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());
192 this->startWarningThread(subscribedTopicsMsg, approxSync);
198 ParametersMap::iterator iter = parameters.find(Parameters::kRegStrategy());
199 if(iter != parameters.end() && iter->second.compare(
"0") != 0)
201 ROS_WARN(
"RGBDICP odometry works only with \"Reg/Strategy\"=2. Ignoring value %s.", iter->second.c_str());
207 const sensor_msgs::ImageConstPtr& image,
208 const sensor_msgs::ImageConstPtr& depth,
209 const sensor_msgs::CameraInfoConstPtr& cameraInfo,
210 const sensor_msgs::LaserScanConstPtr& scanMsg)
212 sensor_msgs::PointCloud2ConstPtr cloudMsg;
213 callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
217 const sensor_msgs::ImageConstPtr& image,
218 const sensor_msgs::ImageConstPtr& depth,
219 const sensor_msgs::CameraInfoConstPtr& cameraInfo,
220 const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
222 sensor_msgs::LaserScanConstPtr scanMsg;
223 callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
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)
234 if(!this->isPaused())
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());
255 ros::Time stamp = image->header.stamp > depth->header.stamp? image->header.stamp : depth->header.stamp;
256 if(scanMsg.get() != 0)
258 if(stamp < scanMsg->
header.stamp)
260 stamp = scanMsg->header.stamp;
263 else if(cloudMsg.get() != 0)
265 if(stamp < cloudMsg->
header.stamp)
267 stamp = cloudMsg->header.stamp;
272 if(localTransform.
isNull())
277 if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
285 int maxLaserScans = 0;
286 if(scanMsg.get() != 0)
290 scanMsg->header.frame_id,
291 scanMsg->header.stamp +
ros::Duration().
fromSec(scanMsg->ranges.size()*scanMsg->time_increment));
292 if(localScanTransform.
isNull())
294 ROS_ERROR(
"TF of received laser scan topic at time %fs is not set, aborting odometry update.", scanMsg->header.stamp.toSec());
299 sensor_msgs::PointCloud2 scanOut;
302 pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(
new pcl::PointCloud<pcl::PointXYZ>);
304 pclScan->is_dense =
true;
306 maxLaserScans = (int)scanMsg->ranges.size();
309 if(scanVoxelSize_ > 0.0
f)
311 float pointsBeforeFiltering = (float)pclScan->size();
313 float ratio = float(pclScan->size()) / pointsBeforeFiltering;
314 maxLaserScans = int(
float(maxLaserScans) * ratio);
316 if(scanNormalK_ > 0 || scanNormalRadius_>0.0
f)
319 pcl::PointCloud<pcl::Normal>::Ptr normals;
320 if(scanVoxelSize_ > 0.0
f)
328 pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(
new pcl::PointCloud<pcl::PointNormal>);
329 pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
338 else if(cloudMsg.get() != 0)
340 bool containNormals =
false;
341 if(scanVoxelSize_ == 0.0
f)
343 for(
unsigned int i=0; i<cloudMsg->fields.size(); ++i)
345 if(cloudMsg->fields[i].name.compare(
"normal_x") == 0)
347 containNormals =
true;
352 localScanTransform =
getTransform(this->frameId(), cloudMsg->header.frame_id, cloudMsg->header.stamp);
353 if(localScanTransform.
isNull())
355 ROS_ERROR(
"TF of received scan cloud at time %fs is not set, aborting rtabmap update.", cloudMsg->header.stamp.toSec());
359 maxLaserScans = scanCloudMaxPoints_;
362 pcl::PointCloud<pcl::PointNormal>::Ptr pclScan(
new pcl::PointCloud<pcl::PointNormal>);
364 if(!pclScan->is_dense)
372 pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(
new pcl::PointCloud<pcl::PointXYZ>);
374 if(!pclScan->is_dense)
381 if(scanVoxelSize_ > 0.0
f)
383 float pointsBeforeFiltering = (float)pclScan->size();
385 float ratio = float(pclScan->size()) / pointsBeforeFiltering;
386 maxLaserScans = int(
float(maxLaserScans) * ratio);
388 if(scanNormalK_ > 0 || scanNormalRadius_>0.0
f)
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);
406 scanMsg.get() != 0 || cloudMsg.get() != 0?maxLaserScans:0,
407 scanMsg.get() != 0?scanMsg->range_max:0,
415 this->processData(data, stamp);
426 delete approxScanSync_;
428 approxScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, _1, _2, _3, _4));
432 delete exactScanSync_;
434 exactScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, _1, _2, _3, _4));
438 delete approxCloudSync_;
440 approxCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, _1, _2, _3, _4));
444 delete exactCloudSync_;
446 exactCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, _1, _2, _3, _4));
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))
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
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_
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)
Connection registerCallback(C &callback)
message_filters::Synchronizer< MyExactScanSyncPolicy > * exactScanSync_
message_filters::Synchronizer< MyApproxCloudSyncPolicy > * approxCloudSync_
Duration & fromSec(double t)
bool param(const std::string ¶m_name, T ¶m_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
virtual ~RGBDICPOdometry()
virtual void updateParameters(ParametersMap ¶meters)
#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()
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)
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)