00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <ros/ros.h>
00029 #include <pluginlib/class_list_macros.h>
00030 #include <nodelet/nodelet.h>
00031
00032 #include <pcl/point_cloud.h>
00033 #include <pcl/point_types.h>
00034 #include <pcl_conversions/pcl_conversions.h>
00035
00036 #include <tf/transform_listener.h>
00037
00038 #include <sensor_msgs/PointCloud2.h>
00039
00040 #include <rtabmap_ros/MsgConversion.h>
00041
00042 #include "rtabmap/core/util3d.h"
00043 #include "rtabmap/core/util3d_filtering.h"
00044 #include "rtabmap/core/util3d_mapping.h"
00045 #include "rtabmap/core/util3d_transforms.h"
00046
00047 namespace rtabmap_ros
00048 {
00049
00050 class ObstaclesDetectionOld : public nodelet::Nodelet
00051 {
00052 public:
00053 ObstaclesDetectionOld() :
00054 frameId_("base_link"),
00055 normalKSearch_(20),
00056 groundNormalAngle_(M_PI_4),
00057 clusterRadius_(0.05),
00058 minClusterSize_(20),
00059 maxObstaclesHeight_(0.0),
00060 maxGroundHeight_(0.0),
00061 segmentFlatObstacles_(false),
00062 waitForTransform_(false),
00063 optimizeForCloseObjects_(false),
00064 projVoxelSize_(0.01)
00065 {}
00066
00067 virtual ~ObstaclesDetectionOld()
00068 {}
00069
00070 private:
00071 virtual void onInit()
00072 {
00073 ros::NodeHandle & nh = getNodeHandle();
00074 ros::NodeHandle & pnh = getPrivateNodeHandle();
00075
00076 int queueSize = 10;
00077 pnh.param("queue_size", queueSize, queueSize);
00078 pnh.param("frame_id", frameId_, frameId_);
00079 pnh.param("normal_k", normalKSearch_, normalKSearch_);
00080 pnh.param("ground_normal_angle", groundNormalAngle_, groundNormalAngle_);
00081 if(pnh.hasParam("normal_estimation_radius") && !pnh.hasParam("cluster_radius"))
00082 {
00083 NODELET_WARN("Parameter \"normal_estimation_radius\" has been renamed "
00084 "to \"cluster_radius\"! Your value is still copied to "
00085 "corresponding parameter. Instead of normal radius, nearest neighbors count "
00086 "\"normal_k\" is used instead (default 20).");
00087 pnh.param("normal_estimation_radius", clusterRadius_, clusterRadius_);
00088 }
00089 else
00090 {
00091 pnh.param("cluster_radius", clusterRadius_, clusterRadius_);
00092 }
00093 pnh.param("min_cluster_size", minClusterSize_, minClusterSize_);
00094 pnh.param("max_obstacles_height", maxObstaclesHeight_, maxObstaclesHeight_);
00095 pnh.param("max_ground_height", maxGroundHeight_, maxGroundHeight_);
00096 pnh.param("detect_flat_obstacles", segmentFlatObstacles_, segmentFlatObstacles_);
00097 pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
00098 pnh.param("optimize_for_close_objects", optimizeForCloseObjects_, optimizeForCloseObjects_);
00099 pnh.param("proj_voxel_size", projVoxelSize_, projVoxelSize_);
00100
00101 cloudSub_ = nh.subscribe("cloud", 1, &ObstaclesDetectionOld::callback, this);
00102
00103 groundPub_ = nh.advertise<sensor_msgs::PointCloud2>("ground", 1);
00104 obstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("obstacles", 1);
00105 projObstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("proj_obstacles", 1);
00106 }
00107
00108
00109
00110 void callback(const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
00111 {
00112 ros::WallTime time = ros::WallTime::now();
00113
00114 if (groundPub_.getNumSubscribers() == 0 && obstaclesPub_.getNumSubscribers() == 0 && projObstaclesPub_.getNumSubscribers() == 0)
00115 {
00116
00117 return;
00118 }
00119
00120 rtabmap::Transform localTransform;
00121 try
00122 {
00123 if(waitForTransform_)
00124 {
00125 if(!tfListener_.waitForTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, ros::Duration(1)))
00126 {
00127 NODELET_ERROR("Could not get transform from %s to %s after 1 second!", frameId_.c_str(), cloudMsg->header.frame_id.c_str());
00128 return;
00129 }
00130 }
00131 tf::StampedTransform tmp;
00132 tfListener_.lookupTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, tmp);
00133 localTransform = rtabmap_ros::transformFromTF(tmp);
00134 }
00135 catch(tf::TransformException & ex)
00136 {
00137 NODELET_ERROR("%s",ex.what());
00138 return;
00139 }
00140
00141 pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud(new pcl::PointCloud<pcl::PointXYZ>);
00142 pcl::fromROSMsg(*cloudMsg, *originalCloud);
00143
00144
00145 pcl::IndicesPtr ground, obstacles;
00146 pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(new pcl::PointCloud<pcl::PointXYZ>);
00147 pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud(new pcl::PointCloud<pcl::PointXYZ>);
00148 pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloudWithoutFlatSurfaces(new pcl::PointCloud<pcl::PointXYZ>);
00149
00150 if(originalCloud->size())
00151 {
00152 originalCloud = rtabmap::util3d::transformPointCloud(originalCloud, localTransform);
00153 if(maxObstaclesHeight_ > 0)
00154 {
00155
00156 originalCloud = rtabmap::util3d::passThrough(originalCloud, "z", std::numeric_limits<int>::min(), maxObstaclesHeight_);
00157 }
00158
00159 if(originalCloud->size())
00160 {
00161 if(!optimizeForCloseObjects_)
00162 {
00163
00164 pcl::IndicesPtr flatObstacles(new std::vector<int>);
00165 rtabmap::util3d::segmentObstaclesFromGround<pcl::PointXYZ>(
00166 originalCloud,
00167 ground,
00168 obstacles,
00169 normalKSearch_,
00170 groundNormalAngle_,
00171 clusterRadius_,
00172 minClusterSize_,
00173 segmentFlatObstacles_,
00174 maxGroundHeight_,
00175 &flatObstacles);
00176
00177 if(groundPub_.getNumSubscribers() &&
00178 ground.get() && ground->size())
00179 {
00180 pcl::copyPointCloud(*originalCloud, *ground, *groundCloud);
00181 }
00182
00183 if((obstaclesPub_.getNumSubscribers() || projObstaclesPub_.getNumSubscribers()) &&
00184 obstacles.get() && obstacles->size())
00185 {
00186
00187 std::set<int> flatObstaclesSet;
00188 if(projObstaclesPub_.getNumSubscribers())
00189 {
00190 flatObstaclesSet.insert(flatObstacles->begin(), flatObstacles->end());
00191 }
00192
00193 obstaclesCloud->resize(obstacles->size());
00194 obstaclesCloudWithoutFlatSurfaces->resize(obstacles->size());
00195
00196 int oi=0;
00197 for(unsigned int i=0; i<obstacles->size(); ++i)
00198 {
00199 obstaclesCloud->points[i] = originalCloud->at(obstacles->at(i));
00200 if(flatObstaclesSet.size() == 0 ||
00201 flatObstaclesSet.find(obstacles->at(i))==flatObstaclesSet.end())
00202 {
00203 obstaclesCloudWithoutFlatSurfaces->points[oi] = obstaclesCloud->points[i];
00204 obstaclesCloudWithoutFlatSurfaces->points[oi].z = 0;
00205 ++oi;
00206 }
00207
00208 }
00209
00210 obstaclesCloudWithoutFlatSurfaces->resize(oi);
00211 if(obstaclesCloudWithoutFlatSurfaces->size() && projVoxelSize_ > 0.0)
00212 {
00213 obstaclesCloudWithoutFlatSurfaces = rtabmap::util3d::voxelize(obstaclesCloudWithoutFlatSurfaces, projVoxelSize_);
00214 }
00215 }
00216 }
00217 else
00218 {
00219
00220
00221
00222
00223
00224
00225
00226
00227 pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud_near = rtabmap::util3d::passThrough(originalCloud, "x", std::numeric_limits<int>::min(), 1.);
00228 pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud_far = rtabmap::util3d::passThrough(originalCloud, "x", 1., std::numeric_limits<int>::max());
00229
00230
00231 rtabmap::util3d::segmentObstaclesFromGround<pcl::PointXYZ>(
00232 originalCloud_near,
00233 ground,
00234 obstacles,
00235 normalKSearch_,
00236 groundNormalAngle_,
00237 clusterRadius_,
00238 minClusterSize_,
00239 segmentFlatObstacles_,
00240 maxGroundHeight_);
00241
00242 if(groundPub_.getNumSubscribers() && ground.get() && ground->size())
00243 {
00244 pcl::copyPointCloud(*originalCloud_near, *ground, *groundCloud);
00245 ground->clear();
00246 }
00247
00248 if((obstaclesPub_.getNumSubscribers() || projObstaclesPub_.getNumSubscribers()) && obstacles.get() && obstacles->size())
00249 {
00250 pcl::copyPointCloud(*originalCloud_near, *obstacles, *obstaclesCloud);
00251 obstacles->clear();
00252 }
00253
00254
00255 rtabmap::util3d::segmentObstaclesFromGround<pcl::PointXYZ>(
00256 originalCloud_far,
00257 ground,
00258 obstacles,
00259 normalKSearch_,
00260 2.*groundNormalAngle_,
00261 3.*clusterRadius_,
00262 minClusterSize_,
00263 segmentFlatObstacles_,
00264 maxGroundHeight_);
00265
00266 if(groundPub_.getNumSubscribers() && ground.get() && ground->size())
00267 {
00268 pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud2 (new pcl::PointCloud<pcl::PointXYZ>);
00269 pcl::copyPointCloud(*originalCloud_far, *ground, *groundCloud2);
00270 *groundCloud += *groundCloud2;
00271 }
00272
00273
00274 if((obstaclesPub_.getNumSubscribers() || projObstaclesPub_.getNumSubscribers()) && obstacles.get() && obstacles->size())
00275 {
00276 pcl::PointCloud<pcl::PointXYZ>::Ptr obstacles2(new pcl::PointCloud<pcl::PointXYZ>);
00277 pcl::copyPointCloud(*originalCloud_far, *obstacles, *obstacles2);
00278 *obstaclesCloud += *obstacles2;
00279 }
00280 }
00281
00282 if(!localTransform.isIdentity())
00283 {
00284
00285 rtabmap::Transform localTransformInv = localTransform.inverse();
00286 if(groundCloud->size())
00287 {
00288 groundCloud = rtabmap::util3d::transformPointCloud(groundCloud, localTransformInv);
00289 }
00290 if(obstaclesCloud->size())
00291 {
00292 obstaclesCloud = rtabmap::util3d::transformPointCloud(obstaclesCloud, localTransformInv);
00293 }
00294 }
00295 }
00296 }
00297
00298 if(groundPub_.getNumSubscribers())
00299 {
00300 sensor_msgs::PointCloud2 rosCloud;
00301 pcl::toROSMsg(*groundCloud, rosCloud);
00302 rosCloud.header = cloudMsg->header;
00303
00304
00305 groundPub_.publish(rosCloud);
00306 }
00307
00308 if(obstaclesPub_.getNumSubscribers())
00309 {
00310 sensor_msgs::PointCloud2 rosCloud;
00311 pcl::toROSMsg(*obstaclesCloud, rosCloud);
00312 rosCloud.header = cloudMsg->header;
00313
00314
00315 obstaclesPub_.publish(rosCloud);
00316 }
00317
00318 if(projObstaclesPub_.getNumSubscribers())
00319 {
00320 sensor_msgs::PointCloud2 rosCloud;
00321 pcl::toROSMsg(*obstaclesCloudWithoutFlatSurfaces, rosCloud);
00322 rosCloud.header.stamp = cloudMsg->header.stamp;
00323 rosCloud.header.frame_id = frameId_;
00324
00325
00326 projObstaclesPub_.publish(rosCloud);
00327 }
00328
00329 NODELET_DEBUG("Obstacles segmentation time = %f s", (ros::WallTime::now() - time).toSec());
00330 }
00331
00332 private:
00333 std::string frameId_;
00334 int normalKSearch_;
00335 double groundNormalAngle_;
00336 double clusterRadius_;
00337 int minClusterSize_;
00338 double maxObstaclesHeight_;
00339 double maxGroundHeight_;
00340 bool segmentFlatObstacles_;
00341 bool waitForTransform_;
00342 bool optimizeForCloseObjects_;
00343 double projVoxelSize_;
00344
00345 tf::TransformListener tfListener_;
00346
00347 ros::Publisher groundPub_;
00348 ros::Publisher obstaclesPub_;
00349 ros::Publisher projObstaclesPub_;
00350
00351 ros::Subscriber cloudSub_;
00352 };
00353
00354 PLUGINLIB_EXPORT_CLASS(rtabmap_ros::ObstaclesDetectionOld, nodelet::Nodelet);
00355 }
00356
00357