region_adjacency_graph.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
38 
39 #if ( CV_MAJOR_VERSION >= 4)
40 #include <opencv2/imgproc/types_c.h>
41 #endif
42 
43 namespace jsk_pcl_ros
44 {
46  {
47 
48  }
49 
51  const std::vector<pcl::PointCloud<PointT>::Ptr> &cloud_clusters,
52  const std::vector<pcl::PointCloud<pcl::Normal>::Ptr> &normal_clusters,
53  const pcl::PointCloud<pcl::PointXYZ>::Ptr centroids,
54  std::vector<std::vector<int> > &neigbor_indices,
55  const int edge_weight_criteria)
56  {
57  if (cloud_clusters.empty() || normal_clusters.empty() ||
58  centroids->empty() || neigbor_indices.empty()) {
59  ROS_ERROR("ERROR: Cannot Generate RAG of empty data...");
60  return;
61  }
62  const int comparision_points_size = 100;
63  if (cloud_clusters.size() == neigbor_indices.size()) {
64  std::vector<VertexDescriptor> vertex_descriptor;
65  for (int j = 0; j < centroids->size(); j++) {
66  VertexDescriptor v_des = boost::add_vertex(
67  VertexProperty(j, centroids->points[j], -1), this->graph_);
68  vertex_descriptor.push_back(v_des);
69  }
70  for (int j = 0; j < neigbor_indices.size(); j++) {
71  VertexDescriptor r_vd = vertex_descriptor[j];
72  std::vector<Eigen::Vector3f> center_point;
73  std::vector<Eigen::Vector3f> center_normal;
74  cv::Mat r_histogram;
75  if (edge_weight_criteria == RAG_EDGE_WEIGHT_CONVEX_CRITERIA) {
77  cloud_clusters[j],
78  normal_clusters[j],
79  center_point,
80  center_normal,
81  comparision_points_size);
82  } else if (edge_weight_criteria == RAG_EDGE_WEIGHT_DISTANCE) {
83  if (cloud_clusters[j]->size() > sizeof(char) &&
84  normal_clusters[j]->size() > sizeof(char)) {
86  cloud_clusters[j],
87  normal_clusters[j],
88  r_histogram);
89  }
90  } else {
91  ROS_ERROR("Incorrect Measurement type");
92  return;
93  }
94  for (int i = 0; i < neigbor_indices[j].size(); i++) {
95  int n_index = neigbor_indices[j][i];
96  VertexDescriptor vd = vertex_descriptor[n_index];
97  float distance = 0.0f;
98  if (edge_weight_criteria == RAG_EDGE_WEIGHT_CONVEX_CRITERIA) {
99  std::vector<Eigen::Vector3f> n1_point;
100  std::vector<Eigen::Vector3f> n1_normal;
102  cloud_clusters[n_index],
103  normal_clusters[n_index],
104  n1_point,
105  n1_normal,
106  comparision_points_size);
107  // Common Neigbour
108  int commonIndex = this->getCommonNeigbour(
109  neigbor_indices[j],
110  neigbor_indices[n_index]);
111  if (commonIndex == -1) {
112  // distance = this->getCloudClusterWeightFunction<float>(
113  // center_point, n1_point, center_normal, n1_normal);
114  } else {
115  std::vector<Eigen::Vector3f> n2_point;
116  std::vector<Eigen::Vector3f> n2_normal;
118  cloud_clusters[commonIndex],
119  normal_clusters[commonIndex],
120  n2_point,
121  n2_normal,
122  comparision_points_size);
123  std::vector<std::vector<Eigen::Vector3f> > _points;
124  std::vector<std::vector<Eigen::Vector3f> > _normals;
125  _points.push_back(center_point);
126  _points.push_back(n1_point);
127  // _points.push_back(n2_point);
128  _normals.push_back(center_normal);
129  _normals.push_back(n1_normal);
130  // _normals.push_back(n2_normal);
131  distance = this->getCloudClusterWeightFunction<float>(
132  _points, _normals);
133  }
134  } else if (edge_weight_criteria == RAG_EDGE_WEIGHT_DISTANCE) {
135  if (cloud_clusters[j]->size() > sizeof(char) &&
136  cloud_clusters[n_index]->size() > sizeof(char)) {
137  cv::Mat n_histogram;
139  cloud_clusters[n_index],
140  normal_clusters[n_index],
141  n_histogram);
142  distance = static_cast<float>(
143  cv::compareHist(
144  r_histogram, n_histogram, CV_COMP_CORREL));
145  } else {
146  distance = 0.0f;
147  }
148  } else {
149  distance = 0.0f;
150  }
151  if (r_vd != vd) {
152  bool found = false;
153  EdgeDescriptor e_descriptor;
154  boost::tie(e_descriptor, found) = boost::edge(r_vd, vd, this->graph_);
155  if (!found) {
156  boost::add_edge(
157  r_vd, vd, EdgeProperty(distance), this->graph_);
158  }
159  }
160  }
161  }
162  } else {
163  ROS_WARN("Elements not same size..");
164  }
165  }
166 
167  template<typename T>
169  const std::vector<std::vector<Eigen::Vector3f> > &_points,
170  const std::vector<std::vector<Eigen::Vector3f> > &_normal)
171  {
172 #define ANGLE_THRESHOLD (10)
173  if (_points.size() == 2 && _points.size() == _normal.size()) {
174  T weights_ = -1.0f;
175  int concave_ = 0;
176  int convex_ = 0;
177  for (int i = 0; i < _points[0].size(); i++) {
178  T convexC_ij = this->convexityCriterion<T>(
179  _points[0][i], _points[1][i], _normal[0][i], _normal[1][i]);
180  float angle_ = getVectorAngle(_normal[0][i], _normal[1][i]);
181  if (convexC_ij < 0.0f && angle_ < ANGLE_THRESHOLD) {
182  convexC_ij = abs(convexC_ij);
183  }
184  if (convexC_ij > 0.0) {
185  convex_++;
186  }
187  if (convexC_ij <= 0.0 || std::isnan(convexC_ij)) {
188  concave_++;
189  }
190  /*
191  if (convexC_ij > weights_) {
192  weights_ = convexC_ij;
193  }*/
194  }
195  if (concave_ < convex_ + 20) {
196  weights_ = 1.0f;
197  }
198  return weights_;
199  } else if (_points.size() == 3) {
200  T weights_ = FLT_MIN;
201  for (int i = 0; i < _points[0].size(); i++) {
202  T convexC_ij = this->convexityCriterion<T>(
203  _points[0][i], _points[1][i], _normal[0][i], _normal[1][i]);
204  T convexC_ic = this->convexityCriterion<T>(
205  _points[0][i], _points[2][i], _normal[0][i], _normal[2][i]);
206  T convexC_jc = this->convexityCriterion<T>(
207  _points[1][i], _points[2][i], _normal[1][i], _normal[2][i]);
208  // float angle_ = getVectorAngle(_normal[0][i], _normal[1][i]);
209  // if (angle_ > ANGLE_THRESHOLD && convexC_ij <= 0) {
210  // convexC_ij =/ -1;
211  // }
212  weights_ = std::max(convexC_ij,
213  std::max(convexC_ic, convexC_jc));
214  }
215  return weights_;
216  }
217  }
218 
220  const Eigen::Vector3f &vector1,
221  const Eigen::Vector3f &vector2,
222  bool indegree)
223  {
224  float angle_ = acos(vector1.dot(vector2));
225  if (indegree) {
226  return angle_ * 180/M_PI;
227  } else {
228  return angle_;
229  }
230  }
231 
232  template<typename T>
234  const Eigen::Vector3f &center_point,
235  const Eigen::Vector3f &n1_point,
236  const Eigen::Vector3f &center_normal,
237  const Eigen::Vector3f &neigbour_normal)
238  {
239  Eigen::Vector3f difference_ = center_point - n1_point;
240  difference_ /= difference_.norm();
241  T convexityc = static_cast<T>(center_normal.dot(difference_) -
242  neigbour_normal.dot(difference_));
243  return convexityc;
244  }
245 
247  pcl::PointCloud<PointT>::Ptr cloud,
248  pcl::PointCloud<pcl::Normal>::Ptr normal,
249  std::vector<Eigen::Vector3f> &point_vector,
250  std::vector<Eigen::Vector3f> &normal_vector,
251  int gen_sz)
252  {
253  for (int i = 0; i < std::max(gen_sz, (int)cloud->size()); i++) {
254  int _idx = rand() % cloud->size();
255  Eigen::Vector3f cv = cloud->points[_idx].getVector3fMap();
256  Eigen::Vector3f nv = Eigen::Vector3f(
257  normal->points[_idx].normal_x,
258  normal->points[_idx].normal_y,
259  normal->points[_idx].normal_z);
260  point_vector.push_back(cv);
261  normal_vector.push_back(nv);
262  }
263  }
264 
266  const int _threshold)
267  {
268  if (num_vertices(this->graph_) == 0) {
269  ROS_ERROR("ERROR: Cannot Merge Empty RAG ...");
270  return;
271  }
272  IndexMap index_map = get(boost::vertex_index, this->graph_);
273  EdgePropertyAccess edge_weights = get(boost::edge_weight, this->graph_);
274  VertexIterator i, end;
275  int label = -1;
276  for (boost::tie(i, end) = vertices(this->graph_); i != end; i++) {
277  if (this->graph_[*i].v_label == -1) {
278  graph_[*i].v_label = ++label;
279  }
280  AdjacencyIterator ai, a_end;
281  boost::tie(ai, a_end) = adjacent_vertices(*i, this->graph_);
282  for (; ai != a_end; ++ai) {
283  bool found = false;
284  EdgeDescriptor e_descriptor;
285  boost::tie(e_descriptor, found) = boost::edge(*i, *ai, this->graph_);
286  if (found) {
287  EdgeValue edge_val = boost::get(
288  boost::edge_weight, this->graph_, e_descriptor);
289  float weights_ = edge_val;
290  if (weights_ < _threshold) {
291  remove_edge(e_descriptor, this->graph_);
292  } else {
293  if (this->graph_[*ai].v_label == -1) {
294  this->graph_[*ai].v_label = this->graph_[*i].v_label;
295  }
296  }
297  }
298  }
299  }
300 #ifdef DEBUG
301  // this->printGraph(this->graph_);
302  std::cout << "\nPRINT INFO. \n --Graph Size: "
303  << num_vertices(this->graph_) <<
304  std::endl << "--Total Label: " << label << "\n\n";
305 #endif // DEBUG
306  }
307 
309  const std::vector<int> &c1_neigbour,
310  const std::vector<int> &c2_neigbour)
311  {
312  int commonIndex = -1;
313  for (int j = 0; j < c1_neigbour.size(); j++) {
314  int c1_val = c1_neigbour[j];
315  for (int i = 0; i < c2_neigbour.size(); i++) {
316  int c2_val = c2_neigbour[i];
317  if (c1_val == c2_val) {
318  commonIndex = c1_val;
319  break;
320  }
321  }
322  }
323  return commonIndex;
324  }
325 
327  std::vector<int> &labelMD)
328  {
329  labelMD.clear();
330  VertexIterator i, end;
331  for (boost::tie(i, end) = vertices(this->graph_); i != end; ++i) {
332  labelMD.push_back(static_cast<int>(this->graph_[*i].v_label));
333  }
334  }
335 
337  const Graph &_graph)
338  {
339  VertexIterator i, end;
340  for (boost::tie(i, end) = vertices(_graph); i != end; ++i) {
341  AdjacencyIterator ai, a_end;
342  boost::tie(ai, a_end) = adjacent_vertices(*i, _graph);
343  std::cout << *i << "\t" << _graph[*i].v_label << std::endl;
344  }
345  }
346 
348  const pcl::PointCloud<PointT>::Ptr _cloud,
349  const pcl::PointCloud<pcl::Normal>::Ptr _normal,
350  cv::Mat &_histogram)
351  {
352  pcl::VFHEstimation<PointT,
353  pcl::Normal,
354  pcl::VFHSignature308> vfh;
355  vfh.setInputCloud(_cloud);
356  vfh.setInputNormals(_normal);
357  pcl::search::KdTree<PointT>::Ptr tree(
358  new pcl::search::KdTree<PointT>);
359  vfh.setSearchMethod(tree);
360  pcl::PointCloud<pcl::VFHSignature308>::Ptr _vfhs(
361  new pcl::PointCloud<pcl::VFHSignature308>());
362  vfh.compute(*_vfhs);
363  _histogram = cv::Mat(sizeof(char), 308, CV_32F);
364  for (int i = 0; i < _histogram.cols; i++) {
365  _histogram.at<float>(0, i) = _vfhs->points[0].histogram[i];
366  }
367  float curvature_ = 0.0f;
368  for (int i = 0; i < _normal->size(); i++) {
369  curvature_ += _normal->points[i].curvature;
370  }
371  curvature_ /= static_cast<float>(_normal->size());
372  cv::normalize(
373  _histogram, _histogram, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
374  }
375 } // namespace jsk_pcl_ros
virtual void splitMergeRAG(const int=0.0f)
void sampleRandomPointsFromCloudCluster(pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, std::vector< Eigen::Vector3f > &, std::vector< Eigen::Vector3f > &, int=3)
label
void computeCloudClusterRPYHistogram(const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &)
end
pointer T
boost::property_map< Graph, boost::vertex_index_t >::type IndexMap
virtual void getCloudClusterLabels(std::vector< int > &)
double max(const OneDataStat &d)
wrapper function for max method for boost::function
boost::graph_traits< Graph >::vertex_descriptor VertexDescriptor
T convexityCriterion(const Eigen::Vector3f &, const Eigen::Vector3f &, const Eigen::Vector3f &, const Eigen::Vector3f &)
#define ROS_WARN(...)
boost::graph_traits< Graph >::vertex_iterator VertexIterator
boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, VertexProperty, EdgeProperty > Graph
size
#define M_PI
T getCloudClusterWeightFunction(const std::vector< std::vector< Eigen::Vector3f > > &, const std::vector< std::vector< Eigen::Vector3f > > &)
float getVectorAngle(const Eigen::Vector3f &, const Eigen::Vector3f &, bool=true)
boost::property_map< Graph, boost::edge_weight_t >::type EdgePropertyAccess
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
boost::property< boost::edge_weight_t, float > EdgeProperty
#define ANGLE_THRESHOLD
int getCommonNeigbour(const std::vector< int > &, const std::vector< int > &)
virtual void generateRAG(const std::vector< pcl::PointCloud< PointT >::Ptr > &, const std::vector< pcl::PointCloud< pcl::Normal >::Ptr > &, const pcl::PointCloud< pcl::PointXYZ >::Ptr, std::vector< std::vector< int > > &, const int=RAG_EDGE_WEIGHT_DISTANCE)
boost::property_traits< boost::property_map< Graph, boost::edge_weight_t >::const_type >::value_type EdgeValue
boost::graph_traits< Graph >::adjacency_iterator AdjacencyIterator
virtual void printGraph(const Graph &)
#define ROS_ERROR(...)
double distance(const urdf::Pose &transform)
boost::graph_traits< Graph >::edge_descriptor EdgeDescriptor


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47