42 DiagnosticNodelet::onInit();
44 jsk_recognition_msgs::ClusterPointIndices>(
45 *
pnh_,
"output/indices", 1);
66 const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
72 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
74 std::vector<pcl::PointCloud<PointT>::Ptr> cloud_clusters;
75 std::vector<pcl::PointCloud<pcl::Normal>::Ptr> normal_clusters;
76 pcl::PointCloud<pcl::PointXYZ>::Ptr centroids(
77 new pcl::PointCloud<pcl::PointXYZ>);
79 cloud, this->
indices_, cloud_clusters, normal_clusters, centroids);
80 std::vector<std::vector<int> > neigbour_idx;
89 rag->RAG_EDGE_WEIGHT_CONVEX_CRITERIA);
90 rag->splitMergeRAG(0.0);
91 std::vector<int> labelMD;
92 rag->getCloudClusterLabels(labelMD);
93 std::map<int, pcl::PointIndices> _indices;
95 cloud_clusters, cloud, labelMD, _indices);
96 std::vector<pcl::PointIndices> all_indices;
97 for (std::map<int, pcl::PointIndices>::iterator it = _indices.begin();
98 it != _indices.end(); it++) {
99 all_indices.push_back((*it).second);
104 jsk_recognition_msgs::ClusterPointIndices ros_indices;
106 all_indices, cloud_msg->header);
107 ros_indices.header = cloud_msg->header;
112 const jsk_recognition_msgs::ClusterPointIndices &indices_msg)
117 std::vector<pcl_msgs::PointIndices> indices =
118 indices_msg.cluster_indices;
119 for (
int i = 0; i < indices.size(); i++) {
120 pcl::PointIndices _index;
127 const pcl::PointCloud<PointT>::Ptr cloud,
128 const std::vector<pcl::PointIndices> &indices,
129 std::vector<pcl::PointCloud<PointT>::Ptr> &cloud_clusters,
130 std::vector<pcl::PointCloud<pcl::Normal>::Ptr> &normal_clusters,
131 pcl::PointCloud<pcl::PointXYZ>::Ptr centroids)
134 pcl::ExtractIndices<PointT>::Ptr eifilter(
135 new pcl::ExtractIndices<PointT>);
136 eifilter->setInputCloud(cloud);
137 for (
int i = 0; i < indices.size(); i++) {
138 pcl::PointIndices::Ptr
index(
new pcl::PointIndices());
139 index->indices = indices[i].indices;
140 eifilter->setIndices(index);
141 pcl::PointCloud<PointT>::Ptr tmp_cloud(
142 new pcl::PointCloud<PointT>);
143 eifilter->filter(*tmp_cloud);
144 if (tmp_cloud->width > 0) {
145 Eigen::Vector4f centroid;
146 pcl::compute3DCentroid<PointT, float>(*cloud, *index, centroid);
147 float ct_x =
static_cast<float>(centroid[0]);
148 float ct_y =
static_cast<float>(centroid[1]);
149 float ct_z =
static_cast<float>(centroid[2]);
150 if (!std::isnan(ct_x) && !std::isnan(ct_y) && !std::isnan(ct_z)) {
151 pcl::PointCloud<pcl::Normal>::Ptr s_normal(
152 new pcl::PointCloud<pcl::Normal>);
154 tmp_cloud, s_normal, 40, 0.05,
false);
155 normal_clusters.push_back(s_normal);
156 centroids->push_back(pcl::PointXYZ(ct_x, ct_y, ct_z));
157 cloud_clusters.push_back(tmp_cloud);
164 const pcl::PointCloud<PointT>::Ptr cloud,
165 pcl::PointCloud<pcl::Normal>::Ptr s_normal,
166 const int k,
const double radius,
bool ksearch)
168 pcl::NormalEstimationOMP<PointT, pcl::Normal> ne;
169 ne.setInputCloud(cloud);
170 ne.setNumberOfThreads(8);
171 pcl::search::KdTree<PointT>::Ptr tree(
172 new pcl::search::KdTree<PointT> ());
173 ne.setSearchMethod(tree);
177 ne.setRadiusSearch(radius);
179 ne.compute(*s_normal);
183 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
184 std::vector<std::vector<int> > &pointIndices,
185 const int k,
const double radius,
bool isneigbour)
187 pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
188 kdtree.setInputCloud(cloud);
189 std::vector<std::vector<float> > pointSquaredDistance;
190 for (
int i = 0; i < cloud->size(); i++) {
191 std::vector<int>pointIdx;
192 std::vector<float> pointSqDist;
193 pcl::PointXYZ searchPoint = cloud->points[i];
195 kdtree.nearestKSearch(searchPoint, k, pointIdx, pointSqDist);
197 kdtree.radiusSearch(searchPoint, radius, pointIdx, pointSqDist);
199 pointIndices.push_back(pointIdx);
200 pointSquaredDistance.push_back(pointSqDist);
207 const std::vector<pcl::PointCloud<PointT>::Ptr> &cloud_clusters,
208 pcl::PointCloud<PointT>::Ptr cloud,
209 const std::vector<int> &labelMD,
210 std::map<int, pcl::PointIndices> &all_indices)
213 for (
int i = 0; i < cloud_clusters.size(); i++) {
214 int _idx = labelMD.at(i);
215 pcl::PointIndices _ind;
216 for (
int j = 0; j < cloud_clusters[i]->size(); j++) {
217 _ind.indices.push_back(icounter++);
219 std::map<int, pcl::PointIndices>::iterator
220 iter = all_indices.find(_idx);
221 if (iter == all_indices.end()) {
223 std::map<int, pcl::PointIndices>::value_type(_idx, _ind));
225 pcl::PointIndices prev_ind = (*iter).second;
226 prev_ind.indices.insert(prev_ind.indices.end(),
227 _ind.indices.begin(),
229 (*iter).second = prev_ind;
void segmentCloud(const pcl::PointCloud< PointT >::Ptr, const std::vector< pcl::PointIndices > &, std::vector< pcl::PointCloud< PointT >::Ptr > &, std::vector< pcl::PointCloud< pcl::Normal >::Ptr > &, pcl::PointCloud< pcl::PointXYZ >::Ptr)
void cloud_cb(const sensor_msgs::PointCloud2::ConstPtr &)
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void getConvexLabelCloudIndices(const std::vector< pcl::PointCloud< PointT >::Ptr > &, pcl::PointCloud< PointT >::Ptr, const std::vector< int > &, std::map< int, pcl::PointIndices > &)
std::vector< pcl::PointIndices > indices_
virtual void unsubscribe()
ros::Subscriber sub_indices_
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
void nearestNeigborSearch(pcl::PointCloud< pcl::PointXYZ >::Ptr, std::vector< std::vector< int > > &, const int=8, const double=0.02, bool=true)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ConvexConnectedVoxels, nodelet::Nodelet)
void indices_cb(const jsk_recognition_msgs::ClusterPointIndices &)
ros::Publisher pub_indices_
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
ros::Subscriber sub_cloud_
void estimatePointCloudNormals(const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, const int=8, const double=0.02, bool=true)