39 #if ( CV_MAJOR_VERSION >= 4) 40 #include <opencv2/imgproc/types_c.h> 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)
57 if (cloud_clusters.empty() || normal_clusters.empty() ||
58 centroids->empty() || neigbor_indices.empty()) {
59 ROS_ERROR(
"ERROR: Cannot Generate RAG of empty data...");
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++) {
68 vertex_descriptor.push_back(v_des);
70 for (
int j = 0; j < neigbor_indices.size(); j++) {
72 std::vector<Eigen::Vector3f> center_point;
73 std::vector<Eigen::Vector3f> center_normal;
81 comparision_points_size);
83 if (cloud_clusters[j]->
size() >
sizeof(
char) &&
84 normal_clusters[j]->
size() >
sizeof(
char)) {
94 for (
int i = 0; i < neigbor_indices[j].size(); i++) {
95 int n_index = neigbor_indices[j][i];
99 std::vector<Eigen::Vector3f> n1_point;
100 std::vector<Eigen::Vector3f> n1_normal;
102 cloud_clusters[n_index],
103 normal_clusters[n_index],
106 comparision_points_size);
110 neigbor_indices[n_index]);
111 if (commonIndex == -1) {
115 std::vector<Eigen::Vector3f> n2_point;
116 std::vector<Eigen::Vector3f> n2_normal;
118 cloud_clusters[commonIndex],
119 normal_clusters[commonIndex],
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);
128 _normals.push_back(center_normal);
129 _normals.push_back(n1_normal);
131 distance = this->getCloudClusterWeightFunction<float>(
135 if (cloud_clusters[j]->
size() >
sizeof(char) &&
136 cloud_clusters[n_index]->
size() >
sizeof(char)) {
139 cloud_clusters[n_index],
140 normal_clusters[n_index],
142 distance =
static_cast<float>(
144 r_histogram, n_histogram, CV_COMP_CORREL));
154 boost::tie(e_descriptor, found) = boost::edge(r_vd, vd, this->
graph_);
163 ROS_WARN(
"Elements not same size..");
169 const std::vector<std::vector<Eigen::Vector3f> > &_points,
170 const std::vector<std::vector<Eigen::Vector3f> > &_normal)
172 #define ANGLE_THRESHOLD (10) 173 if (_points.size() == 2 && _points.size() == _normal.size()) {
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]);
182 convexC_ij =
abs(convexC_ij);
184 if (convexC_ij > 0.0) {
187 if (convexC_ij <= 0.0 || std::isnan(convexC_ij)) {
195 if (concave_ < convex_ + 20) {
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]);
220 const Eigen::Vector3f &vector1,
221 const Eigen::Vector3f &vector2,
224 float angle_ =
acos(vector1.dot(vector2));
226 return angle_ * 180/
M_PI;
234 const Eigen::Vector3f ¢er_point,
235 const Eigen::Vector3f &n1_point,
236 const Eigen::Vector3f ¢er_normal,
237 const Eigen::Vector3f &neigbour_normal)
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_));
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,
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);
266 const int _threshold)
268 if (num_vertices(this->
graph_) == 0) {
269 ROS_ERROR(
"ERROR: Cannot Merge Empty RAG ...");
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;
281 boost::tie(ai, a_end) = adjacent_vertices(*i, this->
graph_);
282 for (; ai != a_end; ++ai) {
285 boost::tie(e_descriptor, found) = boost::edge(*i, *ai, this->
graph_);
288 boost::edge_weight, this->
graph_, e_descriptor);
289 float weights_ = edge_val;
290 if (weights_ < _threshold) {
291 remove_edge(e_descriptor, this->
graph_);
293 if (this->
graph_[*ai].v_label == -1) {
302 std::cout <<
"\nPRINT INFO. \n --Graph Size: " 303 << num_vertices(this->
graph_) <<
304 std::endl <<
"--Total Label: " << label <<
"\n\n";
309 const std::vector<int> &c1_neigbour,
310 const std::vector<int> &c2_neigbour)
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;
327 std::vector<int> &labelMD)
331 for (boost::tie(i, end) = vertices(this->
graph_); i != end; ++i) {
332 labelMD.push_back(static_cast<int>(this->
graph_[*i].v_label));
340 for (boost::tie(i, end) = vertices(_graph); i != end; ++i) {
342 boost::tie(ai, a_end) = adjacent_vertices(*i, _graph);
343 std::cout << *i <<
"\t" << _graph[*i].v_label << std::endl;
348 const pcl::PointCloud<PointT>::Ptr _cloud,
349 const pcl::PointCloud<pcl::Normal>::Ptr _normal,
352 pcl::VFHEstimation<
PointT,
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>());
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];
367 float curvature_ = 0.0f;
368 for (
int i = 0; i < _normal->size(); i++) {
369 curvature_ += _normal->points[i].curvature;
371 curvature_ /=
static_cast<float>(_normal->size());
373 _histogram, _histogram, 0, 1, cv::NORM_MINMAX, -1, cv::Mat());
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)
void computeCloudClusterRPYHistogram(const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &)
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 &)
boost::graph_traits< Graph >::vertex_iterator VertexIterator
boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, VertexProperty, EdgeProperty > Graph
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
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 &)
double distance(const urdf::Pose &transform)
boost::graph_traits< Graph >::edge_descriptor EdgeDescriptor