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_pcl_ros/convex_connected_voxels.h>
00037 
00038 namespace jsk_pcl_ros
00039 {   
00040     void ConvexConnectedVoxels::onInit()
00041     {
00042        DiagnosticNodelet::onInit();
00043        pub_indices_ = advertise<
00044           jsk_recognition_msgs::ClusterPointIndices>(
00045              *pnh_, "output/indices", 1);
00046        onInitPostProcess();
00047    }
00048 
00049     void ConvexConnectedVoxels::subscribe()
00050     {
00051        sub_indices_ = pnh_->subscribe(
00052           "input/indices", 10,
00053           &ConvexConnectedVoxels::indices_cb, this);
00054        sub_cloud_ = pnh_->subscribe(
00055           "input/cloud", 10,
00056           &ConvexConnectedVoxels::cloud_cb, this);
00057     }
00058    
00059     void ConvexConnectedVoxels::unsubscribe()
00060     {
00061        sub_cloud_.shutdown();
00062        sub_indices_.shutdown();
00063     }
00064 
00065     void ConvexConnectedVoxels::cloud_cb(
00066        const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
00067     {
00068        
00069        
00070        
00071        
00072        pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00073        pcl::fromROSMsg(*cloud_msg, *cloud);
00074        std::vector<pcl::PointCloud<PointT>::Ptr> cloud_clusters;
00075        std::vector<pcl::PointCloud<pcl::Normal>::Ptr> normal_clusters;
00076        pcl::PointCloud<pcl::PointXYZ>::Ptr centroids(
00077           new pcl::PointCloud<pcl::PointXYZ>);
00078        this->segmentCloud(
00079           cloud, this->indices_, cloud_clusters, normal_clusters, centroids);
00080        std::vector<std::vector<int> > neigbour_idx;
00081        this->nearestNeigborSearch(centroids, neigbour_idx, 4);
00082        boost::shared_ptr<jsk_pcl_ros::RegionAdjacencyGraph> rag(
00083           new jsk_pcl_ros::RegionAdjacencyGraph);
00084        rag->generateRAG(
00085           cloud_clusters,
00086           normal_clusters,
00087           centroids,
00088           neigbour_idx,
00089           rag->RAG_EDGE_WEIGHT_CONVEX_CRITERIA);
00090        rag->splitMergeRAG(0.0);
00091        std::vector<int> labelMD;
00092        rag->getCloudClusterLabels(labelMD);
00093        std::map<int, pcl::PointIndices> _indices;
00094        this->getConvexLabelCloudIndices(
00095           cloud_clusters, cloud, labelMD, _indices);
00096        std::vector<pcl::PointIndices> all_indices;
00097        for (std::map<int, pcl::PointIndices>::iterator it = _indices.begin();
00098             it != _indices.end(); it++) {
00099           all_indices.push_back((*it).second);
00100        }
00101 
00102        
00103 
00104        jsk_recognition_msgs::ClusterPointIndices ros_indices;
00105        ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
00106           all_indices, cloud_msg->header);
00107        ros_indices.header = cloud_msg->header;
00108        pub_indices_.publish(ros_indices);
00109     }
00110 
00111     void ConvexConnectedVoxels::indices_cb(
00112        const jsk_recognition_msgs::ClusterPointIndices &indices_msg)
00113     {
00114        
00115        vital_checker_->poke();
00116        this->indices_.clear();
00117        std::vector<pcl_msgs::PointIndices> indices =
00118           indices_msg.cluster_indices;
00119        for (int i = 0; i < indices.size(); i++) {
00120           pcl::PointIndices _index;
00121           pcl_conversions::toPCL(indices[i], _index);
00122           this->indices_.push_back(_index);
00123        }
00124     }
00125    
00126     void ConvexConnectedVoxels::segmentCloud(
00127         const pcl::PointCloud<PointT>::Ptr cloud,
00128         const std::vector<pcl::PointIndices> &indices,
00129         std::vector<pcl::PointCloud<PointT>::Ptr> &cloud_clusters,
00130         std::vector<pcl::PointCloud<pcl::Normal>::Ptr> &normal_clusters,
00131         pcl::PointCloud<pcl::PointXYZ>::Ptr centroids)
00132     {
00133         boost::mutex::scoped_lock lock(this->mutex_);
00134         pcl::ExtractIndices<PointT>::Ptr eifilter(
00135            new pcl::ExtractIndices<PointT>);
00136         eifilter->setInputCloud(cloud);
00137         for (int i = 0; i < indices.size(); i++) {
00138            pcl::PointIndices::Ptr index(new pcl::PointIndices());
00139            index->indices = indices[i].indices;
00140            eifilter->setIndices(index);
00141            pcl::PointCloud<PointT>::Ptr tmp_cloud(
00142               new pcl::PointCloud<PointT>);
00143            eifilter->filter(*tmp_cloud);
00144            if (tmp_cloud->width > 0) {
00145              Eigen::Vector4f centroid;
00146              pcl::compute3DCentroid<PointT, float>(*cloud, *index, centroid);
00147              float ct_x = static_cast<float>(centroid[0]);
00148              float ct_y = static_cast<float>(centroid[1]);
00149              float ct_z = static_cast<float>(centroid[2]);
00150              if (!std::isnan(ct_x) && !std::isnan(ct_y) && !std::isnan(ct_z)) {
00151                 pcl::PointCloud<pcl::Normal>::Ptr s_normal(
00152                    new pcl::PointCloud<pcl::Normal>);
00153                 this->estimatePointCloudNormals(
00154                    tmp_cloud, s_normal, 40, 0.05, false);
00155                 normal_clusters.push_back(s_normal);
00156                 centroids->push_back(pcl::PointXYZ(ct_x, ct_y, ct_z));
00157                 cloud_clusters.push_back(tmp_cloud);
00158              }
00159           }
00160         }
00161     }
00162    
00163     void ConvexConnectedVoxels::estimatePointCloudNormals(
00164        const pcl::PointCloud<PointT>::Ptr cloud,
00165        pcl::PointCloud<pcl::Normal>::Ptr s_normal,
00166        const int k, const double radius, bool ksearch)
00167     {
00168        pcl::NormalEstimationOMP<PointT, pcl::Normal> ne;
00169        ne.setInputCloud(cloud);
00170        ne.setNumberOfThreads(8);
00171        pcl::search::KdTree<PointT>::Ptr tree(
00172           new pcl::search::KdTree<PointT> ());
00173        ne.setSearchMethod(tree);
00174        if (ksearch) {
00175           ne.setKSearch(k);
00176        } else {
00177           ne.setRadiusSearch(radius);
00178        }
00179        ne.compute(*s_normal);
00180     }
00181 
00182     void ConvexConnectedVoxels::nearestNeigborSearch(
00183       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00184       std::vector<std::vector<int> > &pointIndices,
00185       const int k, const double radius, bool isneigbour)
00186     {
00187       pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
00188       kdtree.setInputCloud(cloud);
00189       std::vector<std::vector<float> > pointSquaredDistance;
00190       for (int i = 0; i < cloud->size(); i++) {
00191          std::vector<int>pointIdx;
00192          std::vector<float> pointSqDist;
00193          pcl::PointXYZ searchPoint = cloud->points[i];
00194          if (isneigbour) {
00195             kdtree.nearestKSearch(searchPoint, k, pointIdx, pointSqDist);
00196          } else {
00197             kdtree.radiusSearch(searchPoint, radius, pointIdx, pointSqDist);
00198          }
00199          pointIndices.push_back(pointIdx);
00200          pointSquaredDistance.push_back(pointSqDist);
00201          pointIdx.clear();
00202          pointSqDist.clear();
00203       }
00204     }
00205 
00206    void ConvexConnectedVoxels::getConvexLabelCloudIndices(
00207        const std::vector<pcl::PointCloud<PointT>::Ptr> &cloud_clusters,
00208        pcl::PointCloud<PointT>::Ptr cloud,
00209        const std::vector<int> &labelMD,
00210        std::map<int, pcl::PointIndices> &all_indices)
00211    {
00212        int icounter = 0;
00213        for (int i = 0; i < cloud_clusters.size(); i++) {
00214           int _idx = labelMD.at(i); 
00215           pcl::PointIndices _ind;
00216           for (int j = 0; j < cloud_clusters[i]->size(); j++) {
00217              _ind.indices.push_back(icounter++);
00218           }
00219           std::map<int, pcl::PointIndices>::iterator
00220              iter = all_indices.find(_idx);
00221           if (iter == all_indices.end()) {
00222              all_indices.insert(
00223                 std::map<int, pcl::PointIndices>::value_type(_idx, _ind));
00224           } else {
00225              pcl::PointIndices prev_ind = (*iter).second;
00226              prev_ind.indices.insert(prev_ind.indices.end(),
00227                                      _ind.indices.begin(),
00228                                      _ind.indices.end());
00229              (*iter).second = prev_ind;
00230           }
00231        }
00232     }
00233 }  
00234 
00235 #include <pluginlib/class_list_macros.h>
00236 PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ConvexConnectedVoxels, nodelet::Nodelet);