int find_planes(const OpenROVmessages::LaserMsg msg){ ROS_INFO("Entered find_planes"); // Fill cloud with data fill_cloud(msg); // Find planes in the cloud while(temp_cloud->points.size() > 0.1 * nr_points){ seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE); seg.setOptimizeCoefficients (true); // Set method and threshold seg.setMethodType (pcl::SAC_RANSAC); seg.setDistanceThreshold (msg.ransac_threshold); // Set the axis for which to search for perpendicular planes Eigen::Vector3f axis = Eigen::Vector3f(1.0,0.0,0.0); // Set a allowed deviation angle from vector axis seg.setEpsAngle((60*CV_PI)/180); seg.setAxis(axis); // Segment the planes and insert the coefficients and inliers in vectors seg.setInputCloud (temp_cloud); seg.segment (*inliers, *coefficients); // Check that we found a plane from the cloud if (inliers->indices.size () == 0) { std::cerr << "Could not estimate a planar model for the given dataset." << std::endl; break; } // push coeffients onto stack coef_vect.push_back(*coefficients); // Extract the inliers extract.setInputCloud (temp_cloud); extract.setIndices (inliers); // Extract found inliers from cloud extract.setNegative(true); extract.filter(*temp_cloud); } return 0; }
bool compute_object(const int i, std::vector<pcl::PointIndices > &segments) { // Call get_plane, get_cylinder, get_sphere // float plane_score = compute_plane(); // plane_inliers_ has the pc. // float cylinder_score = compute_cylinder(); // cylinder_inliers_ has the pc // Select the lowest score and store it in object_inliers_. // inliers_object_ = (plane_score > cylinder_score ? inliers_plane_ : inliers_cylinder_); inliers_object_ = inliers_plane_; // inliers_object_ = inliers_cylinder_; // Test if the point cloud is too small if (inliers_object_->indices.size() < CUT_THRESHOLD) { std::cerr << "object inliers has " << inliers_object_->indices.size() << " < " << CUT_THRESHOLD << " points. Aborting..." << std::endl; return false; } /* // Debugging info pcl::PointCloud<Point>::Ptr best_object_(new pcl::PointCloud<Point>); pcl::copyPointCloud(*cloud_filtered, *inliers_object_, *best_object_); std::stringstream debug_s0; debug_s0 << "no_cluster_object_" << i << ".pcd"; pcl::io::savePCDFile(debug_s0.str(), *best_object_); */ // Euclidean Clustering std::vector<pcl::PointIndices> clusters; cluster_.setInputCloud(cloud_filtered); cluster_.setIndices(inliers_object_); cluster_.extract(clusters); std::cout << "Number of Euclidian clusters found: " << clusters.size() << std::endl; // Check if there is no clusters if (clusters.size() == 0) { std::cerr << "No clusters found. Aborting..." << std::endl; return false; } main_cluster_.reset(new pcl::PointIndices(clusters.at(0))); // Extract the inliers from the input cloud extract.setInputCloud(cloud_filtered); extract.setIndices(main_cluster_); extract.setNegative(false); pcl::PointCloud<Point>::Ptr cloud_plane(new pcl::PointCloud<Point > ()); extract.filter(*cloud_plane); // Test if cluster[0] is too small if (main_cluster_->indices.size() < CUT_THRESHOLD) { std::cerr << "object cluster[0] has " << main_cluster_->indices.size() << " < " << CUT_THRESHOLD << " points. Not writing to disk..." << std::endl; } else { // Write the inliers to disk std::stringstream debug_s; if (inliers_object_ == inliers_cylinder_) { debug_s << "cylinder_object_" << i << ".pcd"; } else if (inliers_object_ == inliers_plane_) { debug_s << "plane_object_" << i << ".pcd"; } else { debug_s << "unknown_object_" << i << ".pcd"; } pcl::io::savePCDFile(debug_s.str(), *cloud_plane); std::cout << "PointCloud representing the extracted component: " << cloud_plane->points.size() << " data points." << std::endl; // Insert the points to segments for cfg3D pcl::PointIndices::Ptr originalIndices(new pcl::PointIndices()); originalIndices->indices.resize(cloud_plane->size()); for (unsigned int j = 0; j < originalIndices->indices.size(); j++) { originalIndices->indices.at(j) = cloud_plane->points.at(j).rgba; } segments.push_back(*originalIndices); // Debugging for cfg3D pcl::PointCloud<Point>::Ptr cfg_segment_cloud(new pcl::PointCloud<Point > ()); pcl::ExtractIndices<Point> cfg_extract; cfg_extract.setNegative(false); cfg_extract.setInputCloud(cloud); cfg_extract.setIndices(originalIndices); cfg_extract.filter(*cfg_segment_cloud); /* cfg_segment_cloud->points.resize(originalIndices->indices.size()); for (unsigned int j = 0; j < originalIndices->indices.size(); j++) { unsigned int index = originalIndices->indices.at(j); cfg_segment_cloud->points.at(j).x = cloud->points.at(index).x; cfg_segment_cloud->points.at(j).y = cloud->points.at(index).y; cfg_segment_cloud->points.at(j).z = cloud->points.at(index).z; } */ std::stringstream cfg_debug_s; cfg_debug_s << "cfg_debug_segment_" << i << ".pcd"; pcl::io::savePCDFile(cfg_debug_s.str(), *cfg_segment_cloud); } // Remove cluster[0], update cloud_filtered and cloud_normals extract.setNegative(true); extract.filter(*cloud_filtered); extract_normals.setNegative(true); extract_normals.setInputCloud(cloud_normals); extract_normals.setIndices(main_cluster_); extract_normals.filter(*cloud_normals); return true; }
bool compute_object(const int i) { // Call get_plane, get_cylinder, get_sphere float plane_score = compute_plane(); // plane_inliers_ has the pc. float cylinder_score = compute_cylinder(); // cylinder_inliers_ has the pc // Select the lowest score and store it in object_inliers_. inliers_object_ = (plane_score > cylinder_score ? inliers_plane_ : inliers_cylinder_); // inliers_object_ = inliers_plane_; // inliers_object_ = inliers_cylinder_; // Test if the point cloud is too small if (inliers_object_->indices.size() < CUT_THRESHOLD) { std::cerr << "object inliers has "<< inliers_object_->indices.size() << " < " << CUT_THRESHOLD <<" points. Aborting..." << std::endl; return false; } /* // Debugging info pcl::PointCloud<Point>::Ptr best_object_(new pcl::PointCloud<Point>); pcl::copyPointCloud(*cloud_filtered, *inliers_object_, *best_object_); std::stringstream debug_s0; debug_s0 << "no_cluster_object_" << i << ".pcd"; pcl::io::savePCDFile(debug_s0.str(), *best_object_); */ // Euclidean Clustering std::vector<pcl::PointIndices> clusters; cluster_.setInputCloud(cloud_filtered); cluster_.setIndices(inliers_object_); cluster_.extract(clusters); std::cout << "Number of Euclidian clusters found: " << clusters.size() << std::endl; // Check if there is no clusters if (clusters.size() == 0) { std::cerr << "No clusters found. Aborting..." << std::endl; return false; } main_cluster_.reset(new pcl::PointIndices(clusters.at(0))); // Extract the inliers from the input cloud extract.setInputCloud(cloud_filtered); extract.setIndices(main_cluster_); extract.setNegative(false); pcl::PointCloud<Point>::Ptr cloud_plane(new pcl::PointCloud<Point > ()); extract.filter(*cloud_plane); // Test if cluster[0] is too small if (main_cluster_->indices.size() < CUT_THRESHOLD) { std::cerr << "object cluster[0] has "<< main_cluster_->indices.size() << " < " << CUT_THRESHOLD <<" points. Not writing to disk..." << std::endl; } else { // Write the inliers to disk std::stringstream debug_s; if (inliers_object_ == inliers_cylinder_) { debug_s << "cylinder_object_" << i << ".pcd"; } else if (inliers_object_ == inliers_plane_) { debug_s << "plane_object_" << i << ".pcd"; } else { debug_s << "unknown_object_" << i << ".pcd"; } pcl::io::savePCDFile(debug_s.str(), *cloud_plane); std::cout << "PointCloud representing the extracted component: " << cloud_plane->points.size() << " data points." << std::endl; } // Remove cluster[0], update cloud_filtered and cloud_normals extract.setNegative(true); extract.filter(*cloud_filtered); extract_normals.setNegative(true); extract_normals.setInputCloud(cloud_normals); extract_normals.setIndices(main_cluster_); extract_normals.filter(*cloud_normals); return true; }