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