void topicCallback_input(const sensor_msgs::PointCloud2::ConstPtr& msg) { /* protected region user implementation of subscribe callback for input on begin */ pcl::PCLPointCloud2::Ptr pcl_pc(new pcl::PCLPointCloud2 ()); pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_cloud (new pcl::PointCloud<pcl::PointXYZ>); pcl::PCLPointCloud2::Ptr cloud_out (new pcl::PCLPointCloud2 ()); // Transformation into PCL type PointCloud2 pcl_conversions::toPCL((*msg), *(pcl_pc)); // Transformation into PCL type PointCloud<pcl::PointXYZRGB> pcl::fromPCLPointCloud2(*(pcl_pc), *(pcl_cloud)); //////////////////////// // PassThrough filter // //////////////////////// pcl::ConditionOr<pcl::PointXYZ>::Ptr range_cond (new pcl::ConditionOr<pcl::PointXYZ> ()); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("x", pcl::ComparisonOps::GT, robot_pose_x+localconfig.inhib_size))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("x", pcl::ComparisonOps::LT, robot_pose_x-localconfig.inhib_size))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("y", pcl::ComparisonOps::GT, robot_pose_y+localconfig.inhib_size))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("y", pcl::ComparisonOps::LT, robot_pose_y-localconfig.inhib_size))); // build the filter pcl::ConditionalRemoval<pcl::PointXYZ> condrem (range_cond); condrem.setInputCloud (pcl_cloud); condrem.setKeepOrganized(true); // apply filter condrem.filter (*pcl_cloud); // Transformation into ROS type pcl::toPCLPointCloud2(*(pcl_cloud), *(cloud_out)); pcl_conversions::moveFromPCL(*(cloud_out), output_pcloud2); output_ready = true; /* protected region user implementation of subscribe callback for input end */ }
void My_Filter::pclCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud){ pcl::PCLPointCloud2::Ptr pcl_pc(new pcl::PCLPointCloud2 ()); pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_cloud (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr final (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr final2 (new pcl::PointCloud<pcl::PointXYZ>); pcl::PCLPointCloud2::Ptr cloud_out (new pcl::PCLPointCloud2 ()); sensor_msgs::PointCloud2 pc2; std::vector<int> inliers; // Transformation into PCL type PointCloud2 pcl_conversions::toPCL((*cloud), *(pcl_pc)); // Transformation into PCL type PointCloud<pcl::PointXYZRGB> pcl::fromPCLPointCloud2(*(pcl_pc), *(pcl_cloud)); std::list<geometry_msgs::PoseStamped> tmp_list; int robot_counter = 0; for (std::list<geometry_msgs::PoseStamped>::iterator it = robots.begin() ; it != robots.end(); ++it) { if(it->pose.orientation.x > 0.001) { // Robot currently not seen //////////////////////// // PassThrough filter // //////////////////////// pcl::PassThrough<pcl::PointXYZ> pass; pass.setInputCloud (pcl_cloud); pass.setFilterFieldName ("x"); pass.setFilterLimits (it->pose.position.x-DETECTION_DISTANCE-it->pose.orientation.x*0.002, it->pose.position.x+DETECTION_DISTANCE+it->pose.orientation.x*0.002); //pass.setFilterLimitsNegative (true); pass.filter (*final2); pass.setInputCloud (final2); pass.setFilterFieldName ("y"); pass.setFilterLimits (it->pose.position.y-DETECTION_DISTANCE-it->pose.orientation.x*0.002, it->pose.position.y+DETECTION_DISTANCE+it->pose.orientation.x*0.002); //pass.setFilterLimitsNegative (true); pass.filter (*final2); } else { // Robot seen //////////////////////// // PassThrough filter // //////////////////////// pcl::PassThrough<pcl::PointXYZ> pass; pass.setInputCloud (pcl_cloud); pass.setFilterFieldName ("x"); pass.setFilterLimits (it->pose.position.x-DETECTION_DISTANCE, it->pose.position.x+DETECTION_DISTANCE); //pass.setFilterLimitsNegative (true); pass.filter (*final2); pass.setInputCloud (final2); pass.setFilterFieldName ("y"); pass.setFilterLimits (it->pose.position.y-DETECTION_DISTANCE, it->pose.position.y+DETECTION_DISTANCE); //pass.setFilterLimitsNegative (true); pass.filter (*final2); pcl::ConditionOr<pcl::PointXYZ>::Ptr range_cond (new pcl::ConditionOr<pcl::PointXYZ> ()); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("x", pcl::ComparisonOps::GT, it->pose.position.x+DETECTION_DISTANCE))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("x", pcl::ComparisonOps::LT, it->pose.position.x-DETECTION_DISTANCE))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("y", pcl::ComparisonOps::GT, it->pose.position.y+DETECTION_DISTANCE))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("y", pcl::ComparisonOps::LT, it->pose.position.y-DETECTION_DISTANCE))); // build the filter pcl::ConditionalRemoval<pcl::PointXYZ> condrem (range_cond); condrem.setInputCloud (pcl_cloud); condrem.setKeepOrganized(true); // apply filter condrem.filter (*pcl_cloud); } if(final2->size() > 2) { // Something in the box double meanX = 0.0; double meanY = 0.0; for(int i = 0; i < final2->size(); i++) { meanX += final2->at(i).x; meanY += final2->at(i).y; } meanX = meanX / final2->size(); meanY = meanY / final2->size(); //robots.at(robot_counter).pose.position.x = meanX; //robots.at(robot_counter).pose.position.y = meanY; it->pose.position.x = meanX; it->pose.position.y = meanY; char numstr[50]; sprintf(numstr, "/robot_%s_link", it->header.frame_id.c_str()); t = tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(0.0), tf::Vector3(meanX, meanY, 0.0)), ros::Time::now(), "/world", numstr); t.stamp_ = ros::Time::now(); broadcaster.sendTransform(t); it->pose.orientation.x = 0.0; tmp_list.push_front(*it); //std::cout << "size : " << final2->size() << std::endl; } else { // Nothing found in the box it->pose.orientation.x += 1.0; if(it->pose.orientation.x > 100.0) { it->pose.orientation.x = 100.0; } //std::cout << "coef : " << it->pose.orientation.x << std::endl; geometry_msgs::PoseStamped tmp = *it; //robots.push_back(*it); //robots.erase(it); //robots.push_back(tmp); tmp_list.push_back(*it); } robot_counter++; } robots = tmp_list; ///////////////////////////////// // Statistical Outlier Removal // ///////////////////////////////// /* pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor; sor.setInputCloud (pcl_cloud); sor.setMeanK (200); sor.setStddevMulThresh (1.0); sor.filter (*final); */ ////////////////////////////////// // Euclidian Cluster Extraction // ////////////////////////////////// // Creating the KdTree object for the search method of the extraction /* pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>); tree->setInputCloud (pcl_cloud); std::vector<pcl::PointIndices> cluster_indices; pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec; ec.setClusterTolerance (0.05); // 2cm ec.setMinClusterSize (5); ec.setMaxClusterSize (50); ec.setSearchMethod (tree); ec.setInputCloud (pcl_cloud); ec.extract (cluster_indices); std::cout << cluster_indices.size() << std::endl; double x = 0.0; double y = 0.0; for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it) { x = 0.0; y = 0.0; for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++) { x +=pcl_cloud->points[*pit].x; y +=pcl_cloud->points[*pit].y; } x = x / it->indices.size(); y = y / it->indices.size(); std::cout << "x : " << x << " y : " << y << " size : " << it->indices.size() << std::endl; } */ // Transformation into ROS type pcl::toPCLPointCloud2(*(pcl_cloud), *(cloud_out)); pcl_conversions::moveFromPCL(*(cloud_out), pc2); point_cloud_publisher_.publish(pc2); }
void topicCallback_input_cloud(const sensor_msgs::PointCloud2::ConstPtr& msg) { /* protected region user implementation of subscribe callback for input_cloud on begin */ pcl::PCLPointCloud2::Ptr pcl_pc(new pcl::PCLPointCloud2 ()); pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_cloud (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr final (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr final2 (new pcl::PointCloud<pcl::PointXYZ>); pcl::PCLPointCloud2::Ptr cloud_out (new pcl::PCLPointCloud2 ()); sensor_msgs::PointCloud2 pc2; std::vector<int> inliers; // Transformation into PCL type PointCloud2 pcl_conversions::toPCL((*msg), *(pcl_pc)); // Transformation into PCL type PointCloud<pcl::PointXYZRGB> pcl::fromPCLPointCloud2(*(pcl_pc), *(pcl_cloud)); std::list<geometry_msgs::PoseStamped> tmp_list; int robot_counter = 0; for (std::list<geometry_msgs::PoseStamped>::iterator it = robots.begin() ; it != robots.end(); ++it) { if(it->pose.orientation.x > 0.001) { // Robot currently not seen //////////////////////// // PassThrough filter // //////////////////////// pcl::PassThrough<pcl::PointXYZ> pass; pass.setInputCloud (pcl_cloud); pass.setFilterFieldName ("x"); pass.setFilterLimits (it->pose.position.x-localconfig.detection_distance-it->pose.orientation.x*0.002, it->pose.position.x+localconfig.detection_distance+it->pose.orientation.x*0.002); //pass.setFilterLimitsNegative (true); pass.filter (*final2); pass.setInputCloud (final2); pass.setFilterFieldName ("y"); pass.setFilterLimits (it->pose.position.y-localconfig.detection_distance-it->pose.orientation.x*0.002, it->pose.position.y+localconfig.detection_distance+it->pose.orientation.x*0.002); //pass.setFilterLimitsNegative (true); pass.filter (*final2); } else { // Robot seen //////////////////////// // PassThrough filter // //////////////////////// pcl::PassThrough<pcl::PointXYZ> pass; pass.setInputCloud (pcl_cloud); pass.setFilterFieldName ("x"); pass.setFilterLimits (it->pose.position.x-localconfig.detection_distance, it->pose.position.x+localconfig.detection_distance); //pass.setFilterLimitsNegative (true); pass.filter (*final2); pass.setInputCloud (final2); pass.setFilterFieldName ("y"); pass.setFilterLimits (it->pose.position.y-localconfig.detection_distance, it->pose.position.y+localconfig.detection_distance); //pass.setFilterLimitsNegative (true); pass.filter (*final2); pcl::ConditionOr<pcl::PointXYZ>::Ptr range_cond (new pcl::ConditionOr<pcl::PointXYZ> ()); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("x", pcl::ComparisonOps::GT, it->pose.position.x+localconfig.detection_distance))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("x", pcl::ComparisonOps::LT, it->pose.position.x-localconfig.detection_distance))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("y", pcl::ComparisonOps::GT, it->pose.position.y+localconfig.detection_distance))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("y", pcl::ComparisonOps::LT, it->pose.position.y-localconfig.detection_distance))); // build the filter pcl::ConditionalRemoval<pcl::PointXYZ> condrem (range_cond); condrem.setInputCloud (pcl_cloud); condrem.setKeepOrganized(true); // apply filter condrem.filter (*pcl_cloud); } if(final2->size() > 2) { // Something in the box double meanX = 0.0; double meanY = 0.0; for(int i = 0; i < final2->size(); i++) { meanX += final2->at(i).x; meanY += final2->at(i).y; } meanX = meanX / final2->size(); meanY = meanY / final2->size(); //robots.at(robot_counter).pose.position.x = meanX; //robots.at(robot_counter).pose.position.y = meanY; it->pose.position.x = (meanX + it->pose.position.x) / 2.0; it->pose.position.y = (meanY + it->pose.position.y) / 2.0; char numstr[50]; sprintf(numstr, "/robot_%s_link", it->header.frame_id.c_str()); t = tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(0.0), tf::Vector3(meanX, meanY, 0.0)), ros::Time::now(), "/world", numstr); t.stamp_ = ros::Time::now(); broadcaster.sendTransform(t); it->pose.orientation.x = 0.0; tmp_list.push_front(*it); if(it->header.frame_id == "0") { robot1_output_ready = true; } else { robot2_output_ready = true; } //std::cout << "size : " << final2->size() << std::endl; } else { // Nothing found in the box it->pose.orientation.x += 1.0; if(it->pose.orientation.x > 100.0) { it->pose.orientation.x = 100.0; } //std::cout << "coef : " << it->pose.orientation.x << std::endl; geometry_msgs::PoseStamped tmp = *it; //robots.push_back(*it); //robots.erase(it); //robots.push_back(tmp); tmp_list.push_back(*it); } robot_counter++; } robots = tmp_list; /* protected region user implementation of subscribe callback for input_cloud end */ }
int pclTest(const int argc, char** const argv) { if(argc == 1) { std::cout << "Please specify an .OBJ-file!" << std::endl; return -1; } if(pcl::io::loadOBJFile(argv[1], *input) == -1) { PCL_ERROR("Couldn't read file!\n"); return -1; } // Conditional removal: everything y < 650 pcl::ConditionAnd<pcl::PointNormal>::Ptr range_cond(new pcl::ConditionAnd<pcl::PointNormal>()); range_cond->addComparison(pcl::FieldComparison<pcl::PointNormal>::ConstPtr( new pcl::FieldComparison<pcl::PointNormal>("y", pcl::ComparisonOps::GT, 650.0)) ); pcl::ConditionalRemoval<pcl::PointNormal> condrem; condrem.setCondition(range_cond); condrem.setInputCloud(input); condrem.setKeepOrganized(true); condrem.filter(*demeaned); // Conditional removal: every normal -0.5 < n_x < 0.5 /* pcl::ConditionOr<pcl::PointNormal>::Ptr range_cond2(new pcl::ConditionOr<pcl::PointNormal>()); range_cond2->addComparison(pcl::FieldComparison<pcl::PointNormal>::ConstPtr( new pcl::FieldComparison<pcl::PointNormal>("normal_x", pcl::ComparisonOps::GT, 0.5)) ); range_cond2->addComparison(pcl::FieldComparison<pcl::PointNormal>::ConstPtr( new pcl::FieldComparison<pcl::PointNormal>("normal_x", pcl::ComparisonOps::LT, -0.5)) ); condrem.setCondition(range_cond2); condrem.setInputCloud(demeaned); condrem.setKeepOrganized(true); condrem.filter(*demeaned); */ // Remove statistical outliers: neighbour distance > 2.0 pcl::StatisticalOutlierRemoval<pcl::PointNormal> sor; sor.setInputCloud(demeaned); sor.setMeanK(50); sor.setStddevMulThresh(2.0); sor.filter(*demeaned); // Center cloud Eigen::Vector4f centroid; pcl::compute3DCentroid(*demeaned, centroid); pcl::demeanPointCloud(*demeaned, centroid, *demeaned); //pcl::PointCloud<pcl::PointXYZ> float meanXLeft = 0; int numXLeft = 0; float meanXRight = 0; int numXRight = 0; std::vector<float> pointsXLeft; std::vector<float> pointsXRight; for(size_t i = 0; i < demeaned->points.size(); i++) { if(demeaned->points[i].x > 1.0) { meanXLeft += demeaned->points[i].x; pointsXLeft.push_back(demeaned->points[i].x); numXLeft++; } if(demeaned->points[i].x < -1.0) { meanXRight += demeaned->points[i].x; pointsXRight.push_back(demeaned->points[i].x); numXRight++; } } meanXLeft = (meanXLeft / numXLeft); meanXRight = (meanXRight / numXRight); for(float& f : pointsXLeft) { f -= meanXLeft; } for(float& f : pointsXRight) { f -= meanXRight; } float stdDeviationXLeft = 0; float stdDeviationXRight = 0; float planeMeanXLeft = 0; float planeMeanXRight = 0; for(float& f : pointsXLeft) { stdDeviationXLeft += pow(f,2); planeMeanXLeft += f; } stdDeviationXLeft = sqrt(stdDeviationXLeft / (pointsXLeft.size() - 1)); planeMeanXLeft = planeMeanXLeft / pointsXLeft.size(); for(float& f : pointsXRight) { stdDeviationXRight += pow(f,2); planeMeanXRight += f; } //stdDeviationXRight = sqrt((1/(pointsXRight.size() - 1))*stdDeviationXRight); stdDeviationXRight = sqrt(stdDeviationXRight / (pointsXRight.size() - 1)); planeMeanXRight = planeMeanXRight / pointsXRight.size(); std::cout << "Mean left: " << meanXLeft << std::endl; std::cout << "Mean right: " << meanXRight << std::endl; std::cout << "Mean distance: " << (meanXLeft - meanXRight) << std::endl; std::cout << std::endl; std::cout << "Std deviation left plane: " << stdDeviationXLeft << std::endl; std::cout << "Std deviation right plane: " << stdDeviationXRight << std::endl; std::cout << "Mean left plane: " << planeMeanXLeft << std::endl; std::cout << "Mean right plane: " << planeMeanXLeft << std::endl; boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer(new pcl::visualization::PCLVisualizer("Simple Cloud Viewer")); viewer->addPointCloud<pcl::PointNormal>(demeaned, "sample cloud"); viewer->addPointCloudNormals<pcl::PointNormal, pcl::PointNormal>(demeaned,demeaned,1,2.0f); viewer->addCoordinateSystem(1.0); viewer->initCameraParameters(); viewer->registerMouseCallback(mouseEventOccurred, (void*)&viewer); while(!viewer->wasStopped()) { viewer->spinOnce(100); boost::this_thread::sleep (boost::posix_time::microseconds (100000)); } return 0; }
void laserPointsCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud_in) { tf::StampedTransform laser_transform; if(!tf_listener->waitForTransform( "/map", "/head_hokuyo_frame", cloud_in->header.stamp, ros::Duration(1.0))) { ROS_WARN("Transform from /map to /head_hokuyo_frame failed"); return; } tf_listener->lookupTransform("/map", "/head_hokuyo_frame", cloud_in->header.stamp, laser_transform); octomap::point3d laser_origin = octomap::pointTfToOctomap(laser_transform.getOrigin()); pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_raw_cloud(new pcl::PointCloud<pcl::PointXYZ>); pcl::fromROSMsg(*cloud_in, *pcl_raw_cloud); // filter out the points on the robot pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_robot_filtered_cloud(new pcl::PointCloud<pcl::PointXYZ>); pcl::ConditionOr<pcl::PointXYZ>::Ptr range_cond (new pcl::ConditionOr<pcl::PointXYZ>()); range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr ( new pcl::FieldComparison<pcl::PointXYZ>("x", pcl::ComparisonOps::GE, 0.25))); range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr ( new pcl::FieldComparison<pcl::PointXYZ>("x", pcl::ComparisonOps::LE, -0.25))); range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr ( new pcl::FieldComparison<pcl::PointXYZ>("y", pcl::ComparisonOps::GE, 0.25))); range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr ( new pcl::FieldComparison<pcl::PointXYZ>("y", pcl::ComparisonOps::LE, -0.25))); range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr ( new pcl::FieldComparison<pcl::PointXYZ>("z", pcl::ComparisonOps::GE, 1.2))); range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr ( new pcl::FieldComparison<pcl::PointXYZ>("z", pcl::ComparisonOps::LE, -.1))); pcl::ConditionalRemoval<pcl::PointXYZ> robot_filter(range_cond); robot_filter.setInputCloud(pcl_raw_cloud); robot_filter.setKeepOrganized(true); robot_filter.filter(*pcl_robot_filtered_cloud); ROS_DEBUG("pcl_robot_filtered_cloud size: %lu", pcl_robot_filtered_cloud->points.size()); pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_map_cloud(new pcl::PointCloud<pcl::PointXYZ>); if(!tf_listener->waitForTransform( "/map", "/base_link", cloud_in->header.stamp, ros::Duration(1.0))) { ROS_WARN("Transform from /map to /base_link failed"); return; } pcl_ros::transformPointCloud("/map", cloud_in->header.stamp, *pcl_robot_filtered_cloud, "/base_link", *pcl_map_cloud, *tf_listener); // filter out the ground pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_ground_filtered_cloud(new pcl::PointCloud<pcl::PointXYZ>); pcl::PassThrough<pcl::PointXYZ> ground_filter; ground_filter.setInputCloud(pcl_map_cloud); ground_filter.setFilterFieldName("z"); ground_filter.setFilterLimits(-1, .05); ground_filter.setFilterLimitsNegative(true); ground_filter.filter(*pcl_ground_filtered_cloud); ROS_DEBUG("pcl_ground_filtered_cloud size: %lu", pcl_ground_filtered_cloud->points.size()); // filter out the max range readings pcl::PointIndices::Ptr max_indices(new pcl::PointIndices); int i=0; for(pcl::PointCloud<pcl::PointXYZ>::const_iterator point = pcl_ground_filtered_cloud->points.begin(); point != pcl_ground_filtered_cloud->points.end(); point++) { // if this point is within .03 m of the max sensor reading then we want to remove it double x = point->x - laser_origin.x(); double y = point->y - laser_origin.y(); double z = point->z - laser_origin.z(); if(fabs(sqrt(x*x + y*y + z*z) - 30.0) < .04) max_indices->indices.push_back(i); i++; } pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_max_filtered_cloud(new pcl::PointCloud<pcl::PointXYZ>); pcl::ExtractIndices<pcl::PointXYZ> max_filter; max_filter.setInputCloud(pcl_ground_filtered_cloud); max_filter.setKeepOrganized(true); max_filter.setNegative(true); max_filter.setIndices(max_indices); max_filter.filter(*pcl_max_filtered_cloud); ROS_DEBUG("pcl_max_filtered_cloud size: %lu", pcl_max_filtered_cloud->points.size()); // convert to ros datatype as an intermediate step to converting to octomap type sensor_msgs::PointCloud2 filtered_cloud; pcl::toROSMsg(*pcl_max_filtered_cloud, filtered_cloud); ROS_DEBUG("filtered_cloud size: %lu", filtered_cloud.data.size()); // convert to octomap type octomap::Pointcloud octomap_cloud; octomap::pointCloud2ToOctomap(filtered_cloud, octomap_cloud); ROS_DEBUG("octomap pointcloud size: %lu", octomap_cloud.size()); tree->insertPointCloudRays(octomap_cloud, laser_origin, -1, true); ROS_DEBUG("map_changed is now true"); map_changed = true; }
bool filterIt(int argc, char **argv,pcl::PointCloud<PointType>::Ptr cloud, pcl::PointCloud<PointType>::Ptr cloud_filtered) { pcl::ScopeTime time("performance"); time.reset(); if (strcmp(argv[2], "-r") == 0) { if (argc != 5) { std::cout << "All the parameters are not correctly set for the radius removal filter" << std::endl; return 0; } pcl::RadiusOutlierRemoval<PointType> outrem; // build the filter outrem.setInputCloud(cloud); outrem.setRadiusSearch(atof(argv[3])); outrem.setMinNeighborsInRadius (atof(argv[4])); // apply filter outrem.filter (*cloud_filtered); } else if (strcmp(argv[2], "-c") == 0) { if (argc != 6) { std::cout << "All the parameters are not correctly set for the conditional filter" << std::endl; return 0; } // build the condition pcl::ConditionAnd<PointType>::Ptr range_cond (new pcl::ConditionAnd<PointType> ()); range_cond->addComparison (pcl::FieldComparison<PointType>::ConstPtr (new pcl::FieldComparison<PointType> (argv[5], pcl::ComparisonOps::GT, atof ( argv[3] )))); range_cond->addComparison (pcl::FieldComparison<PointType>::ConstPtr (new pcl::FieldComparison<PointType> (argv[5], pcl::ComparisonOps::LT, atof(argv[4]) ))); // build the filter pcl::ConditionalRemoval<PointType> condrem (range_cond); condrem.setInputCloud (cloud); condrem.setKeepOrganized(false); // apply filter condrem.filter (*cloud_filtered); } else if (strcmp(argv[2], "-s") == 0) { if (argc != 5) { std::cout << "All the parameters are not correctly set for the statistical filter" << std::endl; return 0; } // Create the filtering object pcl::StatisticalOutlierRemoval<PointType> sor; sor.setInputCloud (cloud); sor.setMeanK (atof(argv[3])); sor.setStddevMulThresh (atof(argv[4])); sor.filter (*cloud_filtered); } else if (strcmp(argv[2], "-v") == 0) { // Create the filtering object pcl::VoxelGrid<PointType> sor; sor.setDownsampleAllData(true); sor.setInputCloud (cloud); sor.setLeafSize (atof(argv[3]), atof(argv[3]), atof(argv[3])); sor.filter (*cloud_filtered); } else if (strcmp(argv[2], "-av") == 0) { // Create the filtering object pcl::ApproximateVoxelGrid<PointType> sor; sor.setDownsampleAllData(true); sor.setInputCloud (cloud); sor.setLeafSize (atof(argv[3]), atof(argv[3]), atof(argv[3])); sor.filter (*cloud_filtered); } else if (strcmp(argv[2], "-rg") == 0) { // Create the filtering object std::vector<pcl::IndicesPtr> clusteredIndices; pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>); pcl::RegionGrowing<PointType> sor; //sor.setDownsampleAllData(true); sor.setInputCloud (cloud); sor.setGrowingDistance(atof(argv[3])); //sor.setLeafSize (atof(argv[3]), atof(argv[3]), atof(argv[3])); if (atof(argv[4]) > 0){ sor.setEpsAngle(atof(argv[4])); pcl::NormalEstimation<PointType, pcl::Normal> ne; ne.setInputCloud (cloud); pcl::search::KdTree<PointType>::Ptr tree (new pcl::search::KdTree<PointType> ()); ne.setSearchMethod (tree); ne.setRadiusSearch (atof(argv[3])); ne.compute (*cloud_normals); sor.setNormals(cloud_normals); cout << "normals estimed" << endl; } sor.cluster (&clusteredIndices); cout << "clusters? " <<clusteredIndices.size()<<endl; classification<PointType> classif(cloud, clusteredIndices); // pcl::search::KdTree<PointType>::Ptr tree (new pcl::search::KdTree<PointType>); // tree->setInputCloud (cloud); //extractEuclideanClusters ( // const PointCloud<PointT> &cloud, const boost::shared_ptr<search::Search<PointT> > &tree, // float tolerance, std::vector<PointIndices> &clusters, // unsigned int min_pts_per_cluster = 1, unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ()); // boost::shared_ptr<pcl::search::KdTree<PointType> > tree (new pcl::search::KdTree<PointType>); // tree->setInputCloud (cloud); // std::vector<pcl::PointIndices> clusters; // pcl::extractEuclideanClusters<PointType>(cloud, tree, 10, clusters, 100, 200); // pcl::EuclideanClusterExtraction<PointType> ec; // ec.setClusterTolerance ( atof(argv[3]) ); // 2cm // ec.setSearchMethod (tree); // ec.setInputCloud (cloud); // ec.extract (clusteredIndices); // cout << "clusters? " <<clusteredIndices.size()<<endl; pcl::PointCloud<PointType>::Ptr buff_cloud (new pcl::PointCloud<PointType>); for (int i=0; i<clusteredIndices.size(); i++) { //cout << "ok 2" << endl; if (clusteredIndices.operator[](i)->size() < 2300 || clusteredIndices.operator[](i)->size() > 2500) { // cout << "ok 3 " << i << endl; //cout << clusteredIndices[i]->size() << endl; pcl::copyPointCloud(*cloud, clusteredIndices[i].operator*(), *buff_cloud); cloud_filtered->operator+=(*buff_cloud); buff_cloud->clear(); } } if(system("mkdir clusters")) cout << "creating directory \"clusters\""<< endl; saveclusters(clusteredIndices, cloud, "clusters/"); std::stringstream command; command << "pcd_viewer "; for (int i =0 ; i< clusteredIndices.size(); i++) // if (clusteredIndices[i].indices.size() > 2300 && clusteredIndices[i].indices.size() < 2500) command << "clusters/" << i << ".pcd "; if(system (command.str().data())) cout << "visualizing clusters" << endl; FILE *fp; fp = fopen ( "command.sh", "wt" ) ; fprintf ( fp, " %s\n", command.str().data() ); fclose(fp); } else { std::cerr << "please specify the point cloud and the command line arg '-r' or '-c' or '-s' or '-v' or '-av' or 'rg' + param" << std::endl; exit(0); } time.getTime(); return 1; }
void pcl::kinfuLS::WorldModel<PointT>::getWorldAsCubes (const double size, std::vector<typename WorldModel<PointT>::PointCloudPtr> &cubes, std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > &transforms, double overlap) { if(world_->points.size () == 0) { PCL_INFO("The world is empty, returning nothing\n"); return; } PCL_INFO ("Getting world as cubes. World contains %d points.\n", world_->points.size ()); // remove nans from world cloud world_->is_dense = false; std::vector<int> indices; pcl::removeNaNFromPointCloud ( *world_, *world_, indices); PCL_INFO ("World contains %d points after nan removal.\n", world_->points.size ()); // check cube size value double cubeSide = size; if (cubeSide <= 0.0f) { PCL_ERROR ("Size of the cube must be positive and non null (%f given). Setting it to 3.0 meters.\n", cubeSide); cubeSide = 512.0f; } std::cout << "cube size is set to " << cubeSide << std::endl; // check overlap value double step_increment = 1.0f - overlap; if (overlap < 0.0) { PCL_ERROR ("Overlap ratio must be positive or null (%f given). Setting it to 0.0 procent.\n", overlap); step_increment = 1.0f; } if (overlap > 1.0) { PCL_ERROR ("Overlap ratio must be less or equal to 1.0 (%f given). Setting it to 10 procent.\n", overlap); step_increment = 0.1f; } // get world's bounding values on XYZ PointT min, max; pcl::getMinMax3D(*world_, min, max); PCL_INFO ("Bounding box for the world: \n\t [%f - %f] \n\t [%f - %f] \n\t [%f - %f] \n", min.x, max.x, min.y, max.y, min.z, max.z); PointT origin = min; // clear returned vectors cubes.clear(); transforms.clear(); // iterate with box filter while (origin.x < max.x) { origin.y = min.y; while (origin.y < max.y) { origin.z = min.z; while (origin.z < max.z) { // extract cube here PCL_INFO ("Extracting cube at: [%f, %f, %f].\n", origin.x, origin.y, origin.z); // pointcloud for current cube. PointCloudPtr box (new pcl::PointCloud<PointT>); // set conditional filter ConditionAndPtr range_cond (new pcl::ConditionAnd<PointT> ()); range_cond->addComparison (FieldComparisonConstPtr (new pcl::FieldComparison<PointT> ("x", pcl::ComparisonOps::GE, origin.x))); range_cond->addComparison (FieldComparisonConstPtr (new pcl::FieldComparison<PointT> ("x", pcl::ComparisonOps::LT, origin.x + cubeSide))); range_cond->addComparison (FieldComparisonConstPtr (new pcl::FieldComparison<PointT> ("y", pcl::ComparisonOps::GE, origin.y))); range_cond->addComparison (FieldComparisonConstPtr (new pcl::FieldComparison<PointT> ("y", pcl::ComparisonOps::LT, origin.y + cubeSide))); range_cond->addComparison (FieldComparisonConstPtr (new pcl::FieldComparison<PointT> ("z", pcl::ComparisonOps::GE, origin.z))); range_cond->addComparison (FieldComparisonConstPtr (new pcl::FieldComparison<PointT> ("z", pcl::ComparisonOps::LT, origin.z + cubeSide))); // build the filter pcl::ConditionalRemoval<PointT> condrem; condrem.setCondition (range_cond); condrem.setInputCloud (world_); condrem.setKeepOrganized(false); // apply filter condrem.filter (*box); // also push transform along with points. if(box->points.size() > 0) { Eigen::Vector3f transform; transform[0] = origin.x, transform[1] = origin.y, transform[2] = origin.z; transforms.push_back(transform); cubes.push_back(box); } else { PCL_INFO ("Extracted cube was empty, skiping this one.\n"); } origin.z += cubeSide * step_increment; } origin.y += cubeSide * step_increment; } origin.x += cubeSide * step_increment; } /* for(int c = 0 ; c < cubes.size() ; ++c) { std::stringstream name; name << "cloud" << c+1 << ".pcd"; pcl::io::savePCDFileASCII(name.str(), *(cubes[c])); }*/ std::cout << "returning " << cubes.size() << " cubes" << std::endl; }
inline void normal_diff_filter( const pcl::PointCloud<PointT> &in, pcl::PointCloud<PointT> &out, double scale1 = 0.40, ///The smallest scale to use in the DoN filter. double scale2 = 0.60, ///The largest scale to use in the DoN filter. double threshold = 0.6 ///The minimum DoN magnitude to threshold by ) { boost::shared_ptr<pcl::PointCloud<PointT> > in_ptr(in.makeShared()); boost::shared_ptr<pcl::search::KdTree<PointT> > tree_n; tree_n.reset( new pcl::search::KdTree<PointT>(false) ); tree_n->setInputCloud(in_ptr); tree_n->setEpsilon(0.5); if (scale1 >= scale2) { printf("Error: Large scale must be > small scale!"); return; } // Compute normals using both small and large scales at each point pcl::NormalEstimationOMP<PointT, pcl::PointNormal> ne; ne.setInputCloud (in_ptr); ne.setSearchMethod (tree_n); /** * NOTE: setting viewpoint is very important, so that we can ensure * normals are all pointed in the same direction! */ ne.setViewPoint (std::numeric_limits<float>::max (), std::numeric_limits<float>::max (), std::numeric_limits<float>::max ()); // calculate normals with the small scale pcl::PointCloud<pcl::PointNormal>::Ptr normals_small_scale (new pcl::PointCloud<pcl::PointNormal>); ne.setRadiusSearch (scale1); ne.compute (*normals_small_scale); // calculate normals with the large scale pcl::PointCloud<pcl::PointNormal>::Ptr normals_large_scale (new pcl::PointCloud<pcl::PointNormal>); ne.setRadiusSearch (scale2); ne.compute (*normals_large_scale); // Create output cloud for DoN results pcl::PointCloud<pcl::PointNormal>::Ptr doncloud (new pcl::PointCloud<pcl::PointNormal>); pcl::copyPointCloud<PointT, pcl::PointNormal>(in, *doncloud); // Create DoN operator pcl::DifferenceOfNormalsEstimation<PointT, pcl::PointNormal, pcl::PointNormal> don; don.setInputCloud(in_ptr); don.setNormalScaleLarge(normals_large_scale); don.setNormalScaleSmall(normals_small_scale); if (!don.initCompute ()) { std::cerr << "Error: Could not intialize DoN feature operator" << std::endl; return; } // Compute DoN don.computeFeature (*doncloud); // Build the condition for filtering pcl::ConditionOr<pcl::PointNormal>::Ptr range_cond ( new pcl::ConditionOr<pcl::PointNormal> () ); range_cond->addComparison (pcl::FieldComparison<pcl::PointNormal>::ConstPtr ( new pcl::FieldComparison<pcl::PointNormal> ("curvature", pcl::ComparisonOps::GT, threshold)) ); // Build the filter pcl::ConditionalRemoval<pcl::PointNormal> condrem (range_cond, true); condrem.setInputCloud(doncloud); pcl::PointCloud<pcl::PointNormal>::Ptr doncloud_filtered (new pcl::PointCloud<pcl::PointNormal>); // Apply filter condrem.filter(*doncloud_filtered); boost::shared_ptr<pcl::PointIndices> indices(new pcl::PointIndices); condrem.getRemovedIndices(*indices); //std::cout << "Indices: " << indices->indices.size() << " Filtered: " << doncloud_filtered->size () << " data points." << std::endl; pcl::ExtractIndices<PointT> extract; extract.setInputCloud(in_ptr); extract.setIndices(indices); extract.setNegative (true); extract.filter(out); // Save filtered output //std::cout << "In: " << in.size() << " Filtered: " << out.size () << " data points." << std::endl; }
int main (int argc, char** argv) { if (argc != 2) { std::cerr << "please specify command line arg '-r' or '-c'" << std::endl; exit(0); } pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>); // Fill in the cloud data cloud->width = 5; cloud->height = 1; cloud->points.resize (cloud->width * cloud->height); for (size_t i = 0; i < cloud->points.size (); ++i) { cloud->points[i].x = 1024 * rand () / (RAND_MAX + 1.0); cloud->points[i].y = 1024 * rand () / (RAND_MAX + 1.0); cloud->points[i].z = 1024 * rand () / (RAND_MAX + 1.0); } if (strcmp(argv[1], "-r") == 0){ pcl::RadiusOutlierRemoval<pcl::PointXYZ> outrem; // build the filter outrem.setInputCloud(cloud); outrem.setRadiusSearch(0.8); outrem.setMinNeighborsInRadius (2); // apply filter outrem.filter (*cloud_filtered); } else if (strcmp(argv[1], "-c") == 0){ // build the condition pcl::ConditionAnd<pcl::PointXYZ>::Ptr range_cond (new pcl::ConditionAnd<pcl::PointXYZ> ()); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("z", pcl::ComparisonOps::GT, 0.0))); range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (new pcl::FieldComparison<pcl::PointXYZ> ("z", pcl::ComparisonOps::LT, 0.8))); // build the filter pcl::ConditionalRemoval<pcl::PointXYZ> condrem (range_cond); condrem.setInputCloud (cloud); condrem.setKeepOrganized(true); // apply filter condrem.filter (*cloud_filtered); } else{ std::cerr << "please specify command line arg '-r' or '-c'" << std::endl; exit(0); } std::cerr << "Cloud before filtering: " << std::endl; for (size_t i = 0; i < cloud->points.size (); ++i) std::cerr << " " << cloud->points[i].x << " " << cloud->points[i].y << " " << cloud->points[i].z << std::endl; // display pointcloud after filtering std::cerr << "Cloud after filtering: " << std::endl; for (size_t i = 0; i < cloud_filtered->points.size (); ++i) std::cerr << " " << cloud_filtered->points[i].x << " " << cloud_filtered->points[i].y << " " << cloud_filtered->points[i].z << std::endl; return (0); }