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 pnh.
param(
"approx_sync", approxSync, approxSync);
114 pnh.
param(
"queue_size", queueSize_, queueSize_);
115 pnh.
param(
"subscribe_scan_cloud", subscribeScanCloud, subscribeScanCloud);
116 pnh.
param(
"scan_cloud_max_points", scanCloudMaxPoints_, scanCloudMaxPoints_);
117 pnh.
param(
"scan_voxel_size", scanVoxelSize_, scanVoxelSize_);
118 pnh.
param(
"scan_normal_k", scanNormalK_, scanNormalK_);
121 ROS_WARN(
"rtabmap: Parameter \"scan_cloud_normal_k\" has been renamed to \"scan_normal_k\". " 122 "The value is still used. Use \"scan_normal_k\" to avoid this warning.");
123 pnh.
param(
"scan_cloud_normal_k", scanNormalK_, scanNormalK_);
125 pnh.
param(
"scan_normal_radius", scanNormalRadius_, scanNormalRadius_);
126 pnh.
param(
"keep_color", keepColor_, keepColor_);
128 NODELET_INFO(
"RGBDIcpOdometry: approx_sync = %s", approxSync?
"true":
"false");
129 NODELET_INFO(
"RGBDIcpOdometry: queue_size = %d", queueSize_);
130 NODELET_INFO(
"RGBDIcpOdometry: subscribe_scan_cloud = %s", subscribeScanCloud?
"true":
"false");
131 NODELET_INFO(
"RGBDIcpOdometry: scan_cloud_max_points = %d", scanCloudMaxPoints_);
132 NODELET_INFO(
"RGBDIcpOdometry: scan_voxel_size = %f", scanVoxelSize_);
133 NODELET_INFO(
"RGBDIcpOdometry: scan_normal_k = %d", scanNormalK_);
134 NODELET_INFO(
"RGBDIcpOdometry: scan_normal_radius = %f", scanNormalRadius_);
135 NODELET_INFO(
"RGBDIcpOdometry: keep_color = %s", keepColor_?
"true":
"false");
146 image_mono_sub_.subscribe(rgb_it, rgb_nh.
resolveName(
"image"), 1, hintsRgb);
147 image_depth_sub_.subscribe(depth_it, depth_nh.
resolveName(
"image"), 1, hintsDepth);
148 info_sub_.subscribe(rgb_nh,
"camera_info", 1);
150 std::string subscribedTopicsMsg;
151 if(subscribeScanCloud)
153 cloud_sub_.subscribe(nh,
"scan_cloud", 1);
157 approxCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, _1, _2, _3, _4));
162 exactCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, _1, _2, _3, _4));
165 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync):\n %s,\n %s,\n %s, \n %s",
167 approxSync?
"approx":
"exact",
168 image_mono_sub_.getTopic().c_str(),
169 image_depth_sub_.getTopic().c_str(),
170 info_sub_.getTopic().c_str(),
171 cloud_sub_.getTopic().c_str());
175 scan_sub_.subscribe(nh,
"scan", 1);
179 approxScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, _1, _2, _3, _4));
184 exactScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, _1, _2, _3, _4));
187 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync):\n %s \\\n %s \\\n %s \\\n %s",
189 approxSync?
"approx":
"exact",
190 image_mono_sub_.getTopic().c_str(),
191 image_depth_sub_.getTopic().c_str(),
192 info_sub_.getTopic().c_str(),
193 scan_sub_.getTopic().c_str());
195 this->startWarningThread(subscribedTopicsMsg, approxSync);
201 ParametersMap::iterator iter = parameters.find(Parameters::kRegStrategy());
202 if(iter != parameters.end() && iter->second.compare(
"0") != 0)
204 ROS_WARN(
"RGBDICP odometry works only with \"Reg/Strategy\"=2. Ignoring value %s.", iter->second.c_str());
210 const sensor_msgs::ImageConstPtr& image,
211 const sensor_msgs::ImageConstPtr& depth,
212 const sensor_msgs::CameraInfoConstPtr& cameraInfo,
213 const sensor_msgs::LaserScanConstPtr& scanMsg)
215 sensor_msgs::PointCloud2ConstPtr cloudMsg;
216 callbackCommon(image, depth, cameraInfo, scanMsg, cloudMsg);
220 const sensor_msgs::ImageConstPtr& image,
221 const sensor_msgs::ImageConstPtr& depth,
222 const sensor_msgs::CameraInfoConstPtr& cameraInfo,
223 const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
225 sensor_msgs::LaserScanConstPtr scanMsg;
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::LaserScanConstPtr& scanMsg,
234 const sensor_msgs::PointCloud2ConstPtr& cloudMsg)
237 if(!this->isPaused())
251 NODELET_ERROR(
"Input type must be image=mono8,mono16,rgb8,bgr8,rgba8,bgra8 (mono8 " 252 "recommended) and image_depth=16UC1,32FC1,mono16. Types detected: %s %s",
253 image->encoding.c_str(), depth->encoding.c_str());
258 ros::Time stamp = image->header.stamp > depth->header.stamp? image->header.stamp : depth->header.stamp;
259 if(scanMsg.get() != 0)
261 if(stamp < scanMsg->header.stamp)
263 stamp = scanMsg->header.stamp;
266 else if(cloudMsg.get() != 0)
268 if(stamp < cloudMsg->header.stamp)
270 stamp = cloudMsg->header.stamp;
275 if(localTransform.
isNull())
280 if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
291 int maxLaserScans = 0;
292 if(scanMsg.get() != 0)
296 scanMsg->header.frame_id,
297 scanMsg->header.stamp +
ros::Duration().
fromSec(scanMsg->ranges.size()*scanMsg->time_increment));
298 if(localScanTransform.
isNull())
300 ROS_ERROR(
"TF of received laser scan topic at time %fs is not set, aborting odometry update.", scanMsg->header.stamp.toSec());
305 sensor_msgs::PointCloud2 scanOut;
308 pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(
new pcl::PointCloud<pcl::PointXYZ>);
310 pclScan->is_dense =
true;
312 maxLaserScans = (int)scanMsg->ranges.size();
315 if(scanVoxelSize_ > 0.0
f)
317 float pointsBeforeFiltering = (float)pclScan->size();
319 float ratio = float(pclScan->size()) / pointsBeforeFiltering;
320 maxLaserScans = int(
float(maxLaserScans) * ratio);
322 if(scanNormalK_ > 0 || scanNormalRadius_>0.0
f)
325 pcl::PointCloud<pcl::Normal>::Ptr normals;
326 if(scanVoxelSize_ > 0.0
f)
334 pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(
new pcl::PointCloud<pcl::PointNormal>);
335 pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
344 else if(cloudMsg.get() != 0)
346 bool containNormals =
false;
347 if(scanVoxelSize_ == 0.0
f)
349 for(
unsigned int i=0; i<cloudMsg->fields.size(); ++i)
351 if(cloudMsg->fields[i].name.compare(
"normal_x") == 0)
353 containNormals =
true;
358 localScanTransform =
getTransform(this->
frameId(), cloudMsg->header.frame_id, cloudMsg->header.stamp);
359 if(localScanTransform.
isNull())
361 ROS_ERROR(
"TF of received scan cloud at time %fs is not set, aborting rtabmap update.", cloudMsg->header.stamp.toSec());
365 maxLaserScans = scanCloudMaxPoints_;
368 pcl::PointCloud<pcl::PointNormal>::Ptr pclScan(
new pcl::PointCloud<pcl::PointNormal>);
370 if(!pclScan->is_dense)
378 pcl::PointCloud<pcl::PointXYZ>::Ptr pclScan(
new pcl::PointCloud<pcl::PointXYZ>);
380 if(!pclScan->is_dense)
387 if(scanVoxelSize_ > 0.0
f)
389 float pointsBeforeFiltering = (float)pclScan->size();
391 float ratio = float(pclScan->size()) / pointsBeforeFiltering;
392 maxLaserScans = int(
float(maxLaserScans) * ratio);
394 if(scanNormalK_ > 0 || scanNormalRadius_>0.0
f)
397 pcl::PointCloud<pcl::Normal>::Ptr normals =
util3d::computeNormals(pclScan, scanNormalK_, scanNormalRadius_);
398 pcl::PointCloud<pcl::PointNormal>::Ptr pclScanNormal(
new pcl::PointCloud<pcl::PointNormal>);
399 pcl::concatenateFields(*pclScan, *normals, *pclScanNormal);
412 scanMsg.get() != 0 || cloudMsg.get() != 0?maxLaserScans:0,
413 scanMsg.get() != 0?scanMsg->range_max:0,
421 this->processData(data, stamp, image->header.frame_id);
432 delete approxScanSync_;
434 approxScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, _1, _2, _3, _4));
438 delete exactScanSync_;
440 exactScanSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackScan,
this, _1, _2, _3, _4));
444 delete approxCloudSync_;
446 approxCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, _1, _2, _3, _4));
450 delete exactCloudSync_;
452 exactCloudSync_->
registerCallback(boost::bind(&RGBDICPOdometry::callbackCloud,
this, _1, _2, _3, _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))
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)
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true, bool is2D=false, const Transform &transform=Transform())