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/tf.h>
00037 #include <tf/transform_listener.h>
00038
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <sensor_msgs/Image.h>
00041 #include <sensor_msgs/image_encodings.h>
00042 #include <sensor_msgs/CameraInfo.h>
00043 #include <stereo_msgs/DisparityImage.h>
00044
00045 #include <image_transport/image_transport.h>
00046 #include <image_transport/subscriber_filter.h>
00047
00048 #include <image_geometry/pinhole_camera_model.h>
00049
00050 #include <message_filters/sync_policies/approximate_time.h>
00051 #include <message_filters/subscriber.h>
00052
00053 #include <cv_bridge/cv_bridge.h>
00054 #include <opencv2/highgui/highgui.hpp>
00055
00056 #include <rtabmap_ros/MsgConversion.h>
00057
00058 #include "rtabmap/core/util3d.h"
00059
00060 namespace rtabmap_ros
00061 {
00062
00063 class ObstaclesDetection : public nodelet::Nodelet
00064 {
00065 public:
00066 ObstaclesDetection() :
00067 frameId_("base_link"),
00068 normalEstimationRadius_(0.05),
00069 groundNormalAngle_(M_PI_4),
00070 minClusterSize_(20),
00071 maxObstaclesHeight_(0),
00072 waitForTransform_(false)
00073 {}
00074
00075 virtual ~ObstaclesDetection()
00076 {}
00077
00078 private:
00079 virtual void onInit()
00080 {
00081 ros::NodeHandle & nh = getNodeHandle();
00082 ros::NodeHandle & pnh = getPrivateNodeHandle();
00083
00084 int queueSize = 10;
00085 pnh.param("queue_size", queueSize, queueSize);
00086 pnh.param("frame_id", frameId_, frameId_);
00087 pnh.param("normal_estimation_radius", normalEstimationRadius_, normalEstimationRadius_);
00088 pnh.param("ground_normal_angle", groundNormalAngle_, groundNormalAngle_);
00089 pnh.param("min_cluster_size", minClusterSize_, minClusterSize_);
00090 pnh.param("max_obstacles_height", maxObstaclesHeight_, maxObstaclesHeight_);
00091 pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
00092
00093 cloudSub_ = nh.subscribe("cloud", 1, &ObstaclesDetection::callback, this);
00094
00095 groundPub_ = nh.advertise<sensor_msgs::PointCloud2>("ground", 1);
00096 obstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("obstacles", 1);
00097 }
00098
00099
00100
00101 void callback(const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
00102 {
00103 if(groundPub_.getNumSubscribers() || obstaclesPub_.getNumSubscribers())
00104 {
00105 rtabmap::Transform localTransform;
00106 try
00107 {
00108 if(waitForTransform_)
00109 {
00110 if(!tfListener_.waitForTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, ros::Duration(1)))
00111 {
00112 ROS_WARN("Could not get transform from %s to %s after 1 second!", frameId_.c_str(), cloudMsg->header.frame_id.c_str());
00113 return;
00114 }
00115 }
00116 tf::StampedTransform tmp;
00117 tfListener_.lookupTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, tmp);
00118 localTransform = rtabmap_ros::transformFromTF(tmp);
00119 }
00120 catch(tf::TransformException & ex)
00121 {
00122 ROS_WARN("%s",ex.what());
00123 return;
00124 }
00125
00126 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00127 pcl::fromROSMsg(*cloudMsg, *cloud);
00128 pcl::IndicesPtr ground, obstacles;
00129 if(cloud->size())
00130 {
00131 cloud = rtabmap::util3d::transformPointCloud<pcl::PointXYZ>(cloud, localTransform);
00132
00133 if(maxObstaclesHeight_ > 0)
00134 {
00135 cloud = rtabmap::util3d::passThrough<pcl::PointXYZ>(cloud, "z", std::numeric_limits<int>::min(), maxObstaclesHeight_);
00136 }
00137 if(cloud->size())
00138 {
00139 rtabmap::util3d::segmentObstaclesFromGround<pcl::PointXYZ>(cloud,
00140 ground, obstacles, normalEstimationRadius_, groundNormalAngle_, minClusterSize_);
00141 }
00142 }
00143
00144 pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud(new pcl::PointCloud<pcl::PointXYZ>);
00145 if(groundPub_.getNumSubscribers() && ground.get() && ground->size())
00146 {
00147 pcl::copyPointCloud(*cloud, *ground, *groundCloud);
00148 }
00149 pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(new pcl::PointCloud<pcl::PointXYZ>);
00150 if(obstaclesPub_.getNumSubscribers() && obstacles.get() && obstacles->size())
00151 {
00152 pcl::copyPointCloud(*cloud, *obstacles, *obstaclesCloud);
00153 }
00154
00155 if(groundPub_.getNumSubscribers())
00156 {
00157 sensor_msgs::PointCloud2 rosCloud;
00158 pcl::toROSMsg(*groundCloud, rosCloud);
00159 rosCloud.header.stamp = cloudMsg->header.stamp;
00160 rosCloud.header.frame_id = frameId_;
00161
00162
00163 groundPub_.publish(rosCloud);
00164 }
00165
00166 if(obstaclesPub_.getNumSubscribers())
00167 {
00168 sensor_msgs::PointCloud2 rosCloud;
00169 pcl::toROSMsg(*obstaclesCloud, rosCloud);
00170 rosCloud.header.stamp = cloudMsg->header.stamp;
00171 rosCloud.header.frame_id = frameId_;
00172
00173
00174 obstaclesPub_.publish(rosCloud);
00175 }
00176 }
00177 }
00178
00179 private:
00180 std::string frameId_;
00181 double normalEstimationRadius_;
00182 double groundNormalAngle_;
00183 int minClusterSize_;
00184 double maxObstaclesHeight_;
00185 bool waitForTransform_;
00186
00187 tf::TransformListener tfListener_;
00188
00189 ros::Publisher groundPub_;
00190 ros::Publisher obstaclesPub_;
00191
00192 ros::Subscriber cloudSub_;
00193 };
00194
00195 PLUGINLIB_EXPORT_CLASS(rtabmap_ros::ObstaclesDetection, nodelet::Nodelet);
00196 }
00197