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
00029
00030
00031
00032
00033
00034
00035
00036 #include "jsk_recognition_utils/pcl_conversion_util.h"
00037 #include "jsk_recognition_utils/geo_util.h"
00038 #include "jsk_pcl_ros/region_growing_multiple_plane_segmentation.h"
00039 #include <pcl/segmentation/conditional_euclidean_clustering.h>
00040 #include <pcl/sample_consensus/method_types.h>
00041 #include <pcl/sample_consensus/model_types.h>
00042 #include <pcl/segmentation/sac_segmentation.h>
00043
00044 namespace jsk_pcl_ros
00045 {
00046
00047 void RegionGrowingMultiplePlaneSegmentation::onInit()
00048 {
00049 DiagnosticNodelet::onInit();
00050
00051 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00052 dynamic_reconfigure::Server<Config>::CallbackType f =
00053 boost::bind (
00054 &RegionGrowingMultiplePlaneSegmentation::configCallback, this, _1, _2);
00055 srv_->setCallback (f);
00056
00057 pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(
00058 *pnh_, "output/polygons", 1);
00059 pub_inliers_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00060 *pnh_, "output/inliers", 1);
00061 pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
00062 *pnh_, "output/coefficients", 1);
00063 pub_clustering_result_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00064 *pnh_, "output/clustering_result", 1);
00065 pub_latest_time_ = advertise<std_msgs::Float32>(
00066 *pnh_, "output/latest_time", 1);
00067 pub_average_time_ = advertise<std_msgs::Float32>(
00068 *pnh_, "output/average_time", 1);
00069 done_initialization_ = true;
00070 onInitPostProcess();
00071 }
00072
00073 void RegionGrowingMultiplePlaneSegmentation::subscribe()
00074 {
00075 sub_input_.subscribe(*pnh_, "input", 1);
00076 sub_normal_.subscribe(*pnh_, "input_normal", 1);
00077 sync_
00078 = boost::make_shared<
00079 message_filters::Synchronizer<NormalSyncPolicy> >(100);
00080 sync_->connectInput(sub_input_, sub_normal_);
00081 sync_->registerCallback(
00082 boost::bind(&RegionGrowingMultiplePlaneSegmentation::segment, this,
00083 _1, _2));
00084 }
00085
00086 void RegionGrowingMultiplePlaneSegmentation::unsubscribe()
00087 {
00088 sub_input_.unsubscribe();
00089 sub_normal_.unsubscribe();
00090 }
00091
00092 void RegionGrowingMultiplePlaneSegmentation::configCallback(
00093 Config &config, uint32_t level)
00094 {
00095 boost::mutex::scoped_lock lock(mutex_);
00096 angular_threshold_ = config.angular_threshold;
00097 distance_threshold_ = config.distance_threshold;
00098 max_curvature_ = config.max_curvature;
00099 min_size_ = config.min_size;
00100 max_size_ = config.max_size;
00101 min_area_ = config.min_area;
00102 max_area_ = config.max_area;
00103 cluster_tolerance_ = config.cluster_tolerance;
00104 ransac_refine_outlier_distance_threshold_
00105 = config.ransac_refine_outlier_distance_threshold;
00106 ransac_refine_max_iterations_
00107 = config.ransac_refine_max_iterations;
00108 }
00109
00110 void RegionGrowingMultiplePlaneSegmentation::ransacEstimation(
00111 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud,
00112 const pcl::PointIndices::Ptr& indices,
00113 pcl::PointIndices& inliers,
00114 pcl::ModelCoefficients& coefficient)
00115 {
00116 pcl::SACSegmentation<pcl::PointXYZRGB> seg;
00117 seg.setOptimizeCoefficients (true);
00118 seg.setMethodType (pcl::SAC_RANSAC);
00119 seg.setDistanceThreshold (ransac_refine_outlier_distance_threshold_);
00120 seg.setInputCloud(cloud);
00121 seg.setIndices(indices);
00122 seg.setMaxIterations (ransac_refine_max_iterations_);
00123 seg.setModelType (pcl::SACMODEL_PLANE);
00124 seg.segment(inliers, coefficient);
00125 }
00126
00127 void RegionGrowingMultiplePlaneSegmentation::segment(
00128 const sensor_msgs::PointCloud2::ConstPtr& msg,
00129 const sensor_msgs::PointCloud2::ConstPtr& normal_msg)
00130 {
00131 boost::mutex::scoped_lock lock(mutex_);
00132 if (!done_initialization_) {
00133 return;
00134 }
00135 vital_checker_->poke();
00136 {
00137 jsk_recognition_utils::ScopedWallDurationReporter r
00138 = timer_.reporter(pub_latest_time_, pub_average_time_);
00139 pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
00140 pcl::PointCloud<pcl::Normal>::Ptr normal(new pcl::PointCloud<pcl::Normal>);
00141 pcl::fromROSMsg(*msg, *cloud);
00142 pcl::fromROSMsg(*normal_msg, *normal);
00143
00144 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr
00145 all_cloud (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00146 pcl::concatenateFields(*cloud, *normal, *all_cloud);
00147 pcl::PointIndices::Ptr indices (new pcl::PointIndices);
00148 for (size_t i = 0; i < all_cloud->points.size(); i++) {
00149 if (!std::isnan(all_cloud->points[i].x) &&
00150 !std::isnan(all_cloud->points[i].y) &&
00151 !std::isnan(all_cloud->points[i].z) &&
00152 !std::isnan(all_cloud->points[i].normal_x) &&
00153 !std::isnan(all_cloud->points[i].normal_y) &&
00154 !std::isnan(all_cloud->points[i].normal_z) &&
00155 !std::isnan(all_cloud->points[i].curvature)) {
00156 if (all_cloud->points[i].curvature < max_curvature_) {
00157 indices->indices.push_back(i);
00158 }
00159 }
00160 }
00161 pcl::ConditionalEuclideanClustering<pcl::PointXYZRGBNormal> cec (true);
00162
00163
00164 pcl::IndicesClustersPtr clusters (new pcl::IndicesClusters);
00165 cec.setInputCloud (all_cloud);
00166 cec.setIndices(indices);
00167 cec.setClusterTolerance(cluster_tolerance_);
00168 cec.setMinClusterSize(min_size_);
00169
00170 {
00171 boost::mutex::scoped_lock lock2(global_custom_condigion_function_mutex);
00172 setCondifionFunctionParameter(angular_threshold_, distance_threshold_);
00173 cec.setConditionFunction(
00174 &RegionGrowingMultiplePlaneSegmentation::regionGrowingFunction);
00175
00176 cec.segment (*clusters);
00177
00178
00179 }
00180
00181
00182 jsk_recognition_msgs::ClusterPointIndices ros_clustering_result;
00183 ros_clustering_result.cluster_indices
00184 = pcl_conversions::convertToROSPointIndices(*clusters, msg->header);
00185 ros_clustering_result.header = msg->header;
00186 pub_clustering_result_.publish(ros_clustering_result);
00187
00188
00189 std::vector<pcl::PointIndices::Ptr> all_inliers;
00190 std::vector<pcl::ModelCoefficients::Ptr> all_coefficients;
00191 jsk_recognition_msgs::PolygonArray ros_polygon;
00192 ros_polygon.header = msg->header;
00193 for (size_t i = 0; i < clusters->size(); i++) {
00194 pcl::PointIndices::Ptr plane_inliers(new pcl::PointIndices);
00195 pcl::ModelCoefficients::Ptr plane_coefficients(new pcl::ModelCoefficients);
00196 pcl::PointIndices::Ptr cluster = boost::make_shared<pcl::PointIndices>((*clusters)[i]);
00197 ransacEstimation(cloud, cluster,
00198 *plane_inliers, *plane_coefficients);
00199 if (plane_inliers->indices.size() > 0) {
00200 jsk_recognition_utils::ConvexPolygon::Ptr convex
00201 = jsk_recognition_utils::convexFromCoefficientsAndInliers<pcl::PointXYZRGB>(
00202 cloud, plane_inliers, plane_coefficients);
00203 if (convex) {
00204 if (min_area_ > convex->area() || convex->area() > max_area_) {
00205 continue;
00206 }
00207 {
00208
00209 Eigen::Vector3f coefficient_normal(plane_coefficients->values[0],
00210 plane_coefficients->values[1],
00211 plane_coefficients->values[2]);
00212 if (convex->getNormalFromVertices().dot(coefficient_normal) < 0) {
00213 convex = boost::make_shared<jsk_recognition_utils::ConvexPolygon>(convex->flipConvex());
00214 }
00215 }
00216
00217 {
00218 Eigen::Vector3f p = convex->getPointOnPlane();
00219 Eigen::Vector3f n = convex->getNormal();
00220 if (p.dot(n) > 0) {
00221 convex = boost::make_shared<jsk_recognition_utils::ConvexPolygon>(convex->flipConvex());
00222 Eigen::Vector3f new_normal = convex->getNormal();
00223 plane_coefficients->values[0] = new_normal[0];
00224 plane_coefficients->values[1] = new_normal[1];
00225 plane_coefficients->values[2] = new_normal[2];
00226 plane_coefficients->values[3] = convex->getD();
00227 }
00228 }
00229
00230 geometry_msgs::PolygonStamped polygon;
00231 polygon.polygon = convex->toROSMsg();
00232 polygon.header = msg->header;
00233 ros_polygon.polygons.push_back(polygon);
00234 all_inliers.push_back(plane_inliers);
00235 all_coefficients.push_back(plane_coefficients);
00236 }
00237 }
00238 }
00239
00240 jsk_recognition_msgs::ClusterPointIndices ros_indices;
00241 ros_indices.cluster_indices =
00242 pcl_conversions::convertToROSPointIndices(all_inliers, msg->header);
00243 ros_indices.header = msg->header;
00244 pub_inliers_.publish(ros_indices);
00245 jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
00246 ros_coefficients.header = msg->header;
00247 ros_coefficients.coefficients =
00248 pcl_conversions::convertToROSModelCoefficients(
00249 all_coefficients, msg->header);
00250 pub_coefficients_.publish(ros_coefficients);
00251 pub_polygons_.publish(ros_polygon);
00252 }
00253 }
00254
00255 double RegionGrowingMultiplePlaneSegmentation::global_angular_threshold = 0.0;
00256 double RegionGrowingMultiplePlaneSegmentation::global_distance_threshold = 0.0;
00257 boost::mutex RegionGrowingMultiplePlaneSegmentation::global_custom_condigion_function_mutex;
00258 }
00259
00260 #include <pluginlib/class_list_macros.h>
00261 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation, nodelet::Nodelet);