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