32 #include <pcl/point_cloud.h>
33 #include <pcl/point_types.h>
35 #include <pcl/filters/filter.h>
40 #include <sensor_msgs/PointCloud2.h>
66 const std::string & rosName,
67 const std::string & parameterName,
73 rtabmap::ParametersMap::const_iterator
iter =gridParameters.find(parameterName);
74 if(
iter != gridParameters.end())
76 NODELET_ERROR(
"obstacles_detection: Parameter \"%s\" has moved from "
77 "rtabmap_conversions to rtabmap library. Use "
78 "parameter \"%s\" instead. The value is still "
79 "copied to new parameter name.",
81 parameterName.c_str());
83 if(
type.compare(
"float") ||
type.compare(
"double"))
89 else if(
type.compare(
"int") ||
type.compare(
"unsigned int"))
97 NODELET_ERROR(
"Not handled type \"%s\" for parameter \"%s\"",
type.c_str(), parameterName.c_str());
102 NODELET_ERROR(
"Parameter \"%s\" not found in default parameters.", parameterName.c_str());
120 if(pnh.
hasParam(
"optimize_for_close_objects"))
122 NODELET_ERROR(
"\"optimize_for_close_objects\" parameter doesn't exist "
123 "anymore. Use rtabmap_conversions/obstacles_detection_old nodelet to use "
124 "the old interface.");
138 std::string paramValue;
155 if(!paramValue.empty())
157 if(
iter->second.first)
161 NODELET_ERROR(
"obstacles_detection: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
162 iter->first.c_str(),
iter->second.second.c_str(), paramValue.c_str());
166 if(
iter->second.second.empty())
168 NODELET_ERROR(
"obstacles_detection: Parameter \"%s\" doesn't exist anymore!",
169 iter->first.c_str());
173 NODELET_ERROR(
"obstacles_detection: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
174 iter->first.c_str(),
iter->second.second.c_str());
182 for(rtabmap::ParametersMap::iterator
iter=gridParameters.begin();
iter!=gridParameters.end(); ++
iter)
190 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"",
iter->first.c_str(), vStr.c_str());
209 uInsert(parameters, gridParameters);
210 parameterMoved(pnh,
"proj_voxel_size", rtabmap::Parameters::kGridCellSize(), parameters);
211 parameterMoved(pnh,
"ground_normal_angle", rtabmap::Parameters::kGridMaxGroundAngle(), parameters);
212 parameterMoved(pnh,
"min_cluster_size", rtabmap::Parameters::kGridMinClusterSize(), parameters);
213 parameterMoved(pnh,
"normal_estimation_radius", rtabmap::Parameters::kGridClusterRadius(), parameters);
214 parameterMoved(pnh,
"cluster_radius", rtabmap::Parameters::kGridClusterRadius(), parameters);
215 parameterMoved(pnh,
"max_obstacles_height", rtabmap::Parameters::kGridMaxObstacleHeight(), parameters);
216 parameterMoved(pnh,
"max_ground_height", rtabmap::Parameters::kGridMaxGroundHeight(), parameters);
217 parameterMoved(pnh,
"detect_flat_obstacles", rtabmap::Parameters::kGridFlatObstacleDetected(), parameters);
218 parameterMoved(pnh,
"normal_k", rtabmap::Parameters::kGridNormalK(), parameters);
220 UASSERT(
uContains(parameters, rtabmap::Parameters::kGridMapFrameProjection()));
224 NODELET_ERROR(
"obstacles_detection: Parameter \"%s\" is true but map_frame_id is not set!", rtabmap::Parameters::kGridMapFrameProjection().
c_str());
238 void callback(
const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
255 NODELET_ERROR(
"Could not get transform from %s to %s after 1 second!",
frameId_.c_str(), cloudMsg->header.frame_id.c_str());
293 UASSERT_MSG(cloudMsg->data.size() == cloudMsg->row_step*cloudMsg->height,
294 uFormat(
"data=%d row_step=%d height=%d", cloudMsg->data.size(), cloudMsg->row_step, cloudMsg->height).c_str());
296 pcl::PointCloud<pcl::PointXYZ>::Ptr inputCloud(
new pcl::PointCloud<pcl::PointXYZ>);
298 if(inputCloud->isOrganized())
301 pcl::removeNaNFromPointCloud(*inputCloud, *inputCloud,
indices);
303 else if(!inputCloud->is_dense && inputCloud->height == 1)
307 NODELET_WARN(
"Detected possible wrong format of point cloud \"%s\", it is "
308 "indicated that it is not dense, but there is only one row. "
309 "Assuming it is dense... This message will only appear once.",
cloudSub_.
getTopic().c_str());
312 inputCloud->is_dense =
true;
316 pcl::IndicesPtr ground, obstacles;
317 pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(
new pcl::PointCloud<pcl::PointXYZ>);
318 pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud(
new pcl::PointCloud<pcl::PointXYZ>);
319 pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloudWithoutFlatSurfaces(
new pcl::PointCloud<pcl::PointXYZ>);
321 if(inputCloud->size())
325 pcl::IndicesPtr flatObstacles(
new std::vector<int>);
328 pcl::IndicesPtr(
new std::vector<int>),
330 cv::Point3f(localTransform.
x(), localTransform.
y(), localTransform.
z()),
335 if(cloud->size() && ((ground.get() && ground->size()) || (obstacles.get() && obstacles->size())))
338 ground.get() && ground->size())
340 pcl::copyPointCloud(*cloud, *ground, *groundCloud);
344 obstacles.get() && obstacles->size())
347 std::set<int> flatObstaclesSet;
350 flatObstaclesSet.insert(flatObstacles->begin(), flatObstacles->end());
353 obstaclesCloud->resize(obstacles->size());
354 obstaclesCloudWithoutFlatSurfaces->resize(obstacles->size());
357 for(
unsigned int i=0;
i<obstacles->size(); ++
i)
359 obstaclesCloud->points[
i] = cloud->at(obstacles->at(
i));
360 if(flatObstaclesSet.size() == 0 ||
361 flatObstaclesSet.find(obstacles->at(
i))==flatObstaclesSet.end())
363 obstaclesCloudWithoutFlatSurfaces->points[oi] = obstaclesCloud->points[
i];
364 obstaclesCloudWithoutFlatSurfaces->points[oi].z = 0;
370 obstaclesCloudWithoutFlatSurfaces->resize(oi);
373 if(!localTransform.
isIdentity() || !pose.isIdentity())
381 if(obstaclesCloudWithoutFlatSurfaces->size() && !pose.isIdentity())
387 if(groundCloud->size())
391 if(obstaclesCloud->size())
400 ROS_WARN(
"obstacles_detection: Input cloud is empty! (%d x %d, is_dense=%d)", cloudMsg->width, cloudMsg->height, cloudMsg->is_dense?1:0);
405 sensor_msgs::PointCloud2 rosCloud;
407 rosCloud.header = cloudMsg->header;
415 sensor_msgs::PointCloud2 rosCloud;
417 rosCloud.header = cloudMsg->header;
425 sensor_msgs::PointCloud2 rosCloud;
427 rosCloud.header.stamp = cloudMsg->header.stamp;
428 rosCloud.header.frame_id =
frameId_;