32 #include <pcl/point_cloud.h>
33 #include <pcl/point_types.h>
35 #include <pcl/io/pcd_io.h>
36 #include <pcl/filters/voxel_grid.h>
37 #include <pcl/filters/radius_outlier_removal.h>
43 #include <nav_msgs/Odometry.h>
44 #include <sensor_msgs/PointCloud2.h>
51 #include <rtabmap_msgs/OdomInfo.h>
54 #include <rtabmap/core/Version.h>
113 int syncQueueSize = 5;
114 bool subscribeOdomInfo =
false;
116 pnh.
param(
"topic_queue_size", queueSize, queueSize);
119 pnh.
param(
"queue_size", syncQueueSize, syncQueueSize);
120 ROS_WARN(
"Parameter \"queue_size\" has been renamed "
121 "to \"sync_queue_size\" and will be removed "
122 "in future versions! The value (%d) is copied to "
123 "\"sync_queue_size\".", syncQueueSize);
127 pnh.
param(
"sync_queue_size", syncQueueSize, syncQueueSize);
144 pnh.
param(
"subscribe_odom_info", subscribeOdomInfo, subscribeOdomInfo);
167 ROS_ERROR(
"point_cloud_assembler: max_cloud or assembling_time parameters should be set!");
173 std::string subscribedTopicsMsg;
177 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to %s",
181 else if(subscribeOdomInfo)
188 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (exact sync):\n %s,\n %s",
202 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (exact sync):\n %s,\n %s",
216 const sensor_msgs::PointCloud2ConstPtr & cloudMsg,
217 const nav_msgs::OdometryConstPtr & odomMsg)
228 NODELET_WARN(
"Reseting point cloud assembler as null odometry has been received.");
234 const sensor_msgs::PointCloud2ConstPtr & cloudMsg,
235 const nav_msgs::OdometryConstPtr & odomMsg,
236 const rtabmap_msgs::OdomInfoConstPtr & odomInfoMsg)
242 if(odomInfoMsg->keyFrameAdded)
254 NODELET_WARN(
"Reseting point cloud assembler as null odometry has been received.");
259 sensor_msgs::PointCloud2
removeField(
const sensor_msgs::PointCloud2 & input,
const std::string & field)
261 sensor_msgs::PointCloud2 output;
263 std::vector<int> inputFieldIndex;
264 for(
size_t i=0;
i<input.fields.size(); ++
i)
266 if(input.fields[
i].name.compare(field) == 0)
272 sensor_msgs::PointField outputField = input.fields[
i];
273 outputField.offset =
offset;
274 offset += outputField.count * sizeOfPointField(outputField.datatype);
275 output.fields.push_back(outputField);
276 inputFieldIndex.push_back(
i);
279 output.header = input.header;
280 output.height = input.height;
281 output.width = input.width;
282 output.is_bigendian = input.is_bigendian;
283 output.is_dense = input.is_dense;
284 output.point_step =
offset;
285 output.row_step = output.width * output.point_step;
286 output.data.resize(output.height*output.row_step);
287 int total = output.height*output.width;
288 for(
int i=0;
i<total; ++
i)
291 int oi =
i*output.point_step;
292 int pi =
i*input.point_step;
293 for(
size_t j=0;
j<output.fields.size(); ++
j)
295 memcpy(&output.data[oi + output.fields[
j].offset],
296 &input.data[
pi + input.fields[inputFieldIndex[
j]].offset],
297 output.fields[
j].count * sizeOfPointField(output.fields[
j].datatype));
308 UASSERT_MSG(cloudMsg->data.size() == cloudMsg->row_step*cloudMsg->height,
309 uFormat(
"data=%d row_step=%d height=%d", cloudMsg->data.size(), cloudMsg->row_step, cloudMsg->height).c_str());
311 if(skipClouds_<=0 || cloudsSkipped_ >=
skipClouds_)
317 cloudMsg->header.frame_id,
318 cloudMsg->header.stamp,
324 ROS_ERROR(
"Cloud not transform all clouds! Resetting...");
329 bool isMoving =
true;
344 pcl::PCLPointCloud2::Ptr newCloud(
new pcl::PCLPointCloud2);
350 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
356 newCloud->header.stamp = stamp;
360 sensor_msgs::PointCloud2 output;
365 if(!newCloud->is_dense)
373 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
374 bool reachedMaxSize =
379 bool reachedMaxSize =
387 pcl::PCLPointCloud2Ptr assembled(
new pcl::PCLPointCloud2);
390 if(assembled->data.empty())
392 *assembled = *(*iter);
396 pcl::PCLPointCloud2Ptr assembledTmp(
new pcl::PCLPointCloud2);
397 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
398 pcl::concatenate(*assembled, *(*
iter), *assembledTmp);
403 assembledTmp->row_step = assembled->row_step + (*iter)->row_step;
404 assembled = assembledTmp;
408 sensor_msgs::PointCloud2 rosCloud;
412 int x_idx=-1, y_idx=-1, z_idx=-1;
413 for (std::size_t
d = 0;
d < assembled->fields.size (); ++
d)
415 if (assembled->fields[
d].name.compare(
"x")==0)
417 if (assembled->fields[
d].name.compare(
"y")==0)
419 if (assembled->fields[
d].name.compare(
"z")==0)
422 bool overflow =
false;
423 if(x_idx>=0 && y_idx>=0 && z_idx>=0) {
424 Eigen::Vector4f min_p, max_p;
425 pcl::getMinMax3D(assembled, x_idx, y_idx, z_idx, min_p, max_p);
440 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
446 assembled->header.stamp = stamp;
450 pcl::VoxelGrid<pcl::PCLPointCloud2> filter;
452 filter.setInputCloud(assembled);
453 pcl::PCLPointCloud2Ptr output(
new pcl::PCLPointCloud2);
454 filter.filter(*output);
460 pcl::RadiusOutlierRemoval<pcl::PCLPointCloud2> filter;
463 filter.setInputCloud(assembled);
464 pcl::PCLPointCloud2Ptr output(
new pcl::PCLPointCloud2);
465 filter.filter(*output);
477 cloudMsg->header.stamp,
482 ROS_ERROR(
"Cloud not transform back assembled clouds in target frame \"%s\"! Resetting...",
frameId_.c_str());
494 rosCloud.header = cloudMsg->header;
497 rosCloud.header.frame_id =
frameId_;
545 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are "
546 "published (\"$ rostopic hz my_topic\") and the timestamps in their "
547 "header are set. %s",
549 subscribedTopicsMsg.c_str());