narfStruct narf(const sensor_msgs::PointCloud2::Ptr p) { //sensor_msgs::PointCloud2::Ptr s = msg.instantiate<sensor_msgs::PointCloud2>(); pcl::PointCloud<pcl::PointXYZ> point_cloud; pcl::fromROSMsg (*p, point_cloud); pcl::RangeImage range_image; point_cloud.width = (int) point_cloud.points.size (); point_cloud.height = 1; range_image.createFromPointCloud (point_cloud, angular_resolution, pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size); // Extract NARF keypoints pcl::RangeImageBorderExtractor range_image_border_extractor; pcl::NarfKeypoint narf_keypoint_detector; narf_keypoint_detector.setRangeImageBorderExtractor (&range_image_border_extractor); narf_keypoint_detector.setRangeImage (&range_image); narf_keypoint_detector.getParameters ().support_size = support_size; pcl::PointCloud<int> keypoint_indices; narf_keypoint_detector.compute (keypoint_indices); // Extract NARF descriptors for interest points std::vector<int> keypoint_indices2; keypoint_indices2.resize (keypoint_indices.points.size ()); for (unsigned int i=0; i<keypoint_indices.size (); ++i){ // This step is necessary to get the right vector type keypoint_indices2[i]=keypoint_indices.points[i]; } pcl::NarfDescriptor narf_descriptor (&range_image, &keypoint_indices2); narf_descriptor.getParameters ().support_size = support_size; narf_descriptor.getParameters ().rotation_invariant = rotation_invariant; narfStruct ns; //pcl::PointCloud<pcl::Narf36> narf_descriptors; narf_descriptor.compute (ns.narf_descriptors); std::cout << "\nNarf:[36 x " <<ns.narf_descriptors.size ()<< "]\t"; ns.rangeImg = range_image; return ns; }
// ---------------------------------------------------------------------------- void loadFeatures3d(BoWFeatures &features) { typedef pcl::PointXYZ PointType; float angular_resolution = pcl::deg2rad (0.15f); float support_size = 0.1f; features.clear(); features.reserve(files_list_3d.size()); float noise_level = 0.0f; float min_range = 0.0f; int border_size = 1; double acc_media = 0,media=0,scarti=0,varianza=0; //pcl::visualization::RangeImageVisualizer range_image_widget ("Range image"); pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME; pcl::RangeImage::Ptr range_image_ptr (new pcl::RangeImage); pcl::RangeImage& range_image = *range_image_ptr; for (int i = 0; i < files_list_3d.size(); ++i) { clock_t begin = clock(); pcl::PointCloud<PointType>::Ptr point_cloud_wf (new pcl::PointCloud<PointType>); pcl::PointCloud<PointType>::Ptr point_cloud (new pcl::PointCloud<PointType>); pcl::io::loadPCDFile (files_list_3d[i], *point_cloud_wf); //filtraggio valori NaN std::vector<int> indices; pcl::removeNaNFromPointCloud (*point_cloud_wf,*point_cloud_wf,indices); pcl::VoxelGrid<PointType> sor; sor.setInputCloud (point_cloud_wf); sor.setLeafSize (0.01f, 0.01f, 0.01f); sor.filter (*point_cloud); cout << "Estrazione NARF: " << files_list_3d[i] ; Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity()); scene_sensor_pose = Eigen::Affine3f (Eigen::Translation3f ((*point_cloud).sensor_origin_[0], (*point_cloud).sensor_origin_[1], (*point_cloud).sensor_origin_[2])) * Eigen::Affine3f ((*point_cloud).sensor_orientation_); // pcl::visualization::RangeImageVisualizer range_image_widget ("Range image"); range_image.max_no_of_threads = 2; range_image.createFromPointCloud ((*point_cloud),angular_resolution,pcl::deg2rad(360.0f),pcl::deg2rad(180.0f),scene_sensor_pose,coordinate_frame,noise_level,min_range,border_size); range_image.setUnseenToMaxRange(); //saveRangeImagePlanarFilePNG(boost::lexical_cast<string>(i),range_image); //range_image_widget.showRangeImage (range_image); //range_image_widget.spin(); pcl::RangeImageBorderExtractor range_image_border_extractor; pcl::NarfKeypoint narf_keypoint_detector; narf_keypoint_detector.setRangeImageBorderExtractor (&range_image_border_extractor); narf_keypoint_detector.setRangeImage (&range_image); narf_keypoint_detector.getParameters().support_size = support_size; //euristiche, per avvicinarsi al real time narf_keypoint_detector.getParameters().max_no_of_threads = 2; narf_keypoint_detector.getParameters().calculate_sparse_interest_image=false; //false narf_keypoint_detector.getParameters().use_recursive_scale_reduction=true; //true //narf_keypoint_detector.getParameters().add_points_on_straight_edges=true; pcl::PointCloud<int> keypoint_indices; narf_keypoint_detector.compute (keypoint_indices); vector<int> keypoint_indices2; keypoint_indices2.resize (keypoint_indices.points.size ()); for (unsigned int i=0; i<keypoint_indices.size (); ++i) // This step is necessary to get the right vector type keypoint_indices2[i]=keypoint_indices.points[i]; pcl::NarfDescriptor narf_descriptor (&range_image, &keypoint_indices2); narf_descriptor.getParameters().support_size = support_size; narf_descriptor.getParameters().rotation_invariant = true; pcl::PointCloud<pcl::Narf36> narf_descriptors; narf_descriptor.compute (narf_descriptors); clock_t end = clock(); double elapsed_secs = double(end - begin) / CLOCKS_PER_SEC; media = media + elapsed_secs; acc_media = media / (i+1); cout << "media: " << acc_media<<endl; scarti += pow(elapsed_secs-acc_media,2); varianza = sqrt(scarti/(i+1)); cout << "varianza: " << varianza<<endl; cout << ". Estratti "<<narf_descriptors.size ()<<" descrittori. Punti: " <<keypoint_indices.points.size ()<< "."<<endl; features.push_back(vector<vector<float> >()); for (int p = 0; p < narf_descriptors.size(); p++) { vector<float> flot; copy(narf_descriptors[p].descriptor, narf_descriptors[p].descriptor+FNarf::L, back_inserter(flot)); features.back().push_back(flot); flot.clear(); } indices.clear(); range_image_border_extractor.clearData(); narf_keypoint_detector.clearData(); (*range_image_ptr).clear(); keypoint_indices.clear(); keypoint_indices2.clear(); (*point_cloud).clear(); (*point_cloud_wf).clear(); range_image.clear(); narf_descriptors.clear(); narf_descriptor = NULL; } cout << "Estrazione terminata." << endl; }
// -------------- // -----Main----- // -------------- int main (int argc, char** argv) { // -------------------------------------- // -----Parse Command Line Arguments----- // -------------------------------------- if (pcl::console::find_argument (argc, argv, "-h") >= 0) { printUsage (argv[0]); return 0; } if (pcl::console::find_argument (argc, argv, "-m") >= 0) { setUnseenToMaxRange = true; cout << "Setting unseen values in range image to maximum range readings.\n"; } if (pcl::console::parse (argc, argv, "-o", rotation_invariant) >= 0) cout << "Switching rotation invariant feature version "<< (rotation_invariant ? "on" : "off")<<".\n"; int tmp_coordinate_frame; if (pcl::console::parse (argc, argv, "-c", tmp_coordinate_frame) >= 0) { coordinate_frame = pcl::RangeImage::CoordinateFrame (tmp_coordinate_frame); cout << "Using coordinate frame "<< (int)coordinate_frame<<".\n"; } if (pcl::console::parse (argc, argv, "-s", support_size) >= 0) cout << "Setting support size to "<<support_size<<".\n"; if (pcl::console::parse (argc, argv, "-r", angular_resolution) >= 0) cout << "Setting angular resolution to "<<angular_resolution<<"deg.\n"; angular_resolution = pcl::deg2rad (angular_resolution); // ------------------------------------------------------------------ // -----Read pcd file or create example point cloud if not given----- // ------------------------------------------------------------------ pcl::PointCloud<PointType>::Ptr point_cloud_ptr (new pcl::PointCloud<PointType>); pcl::PointCloud<PointType>& point_cloud = *point_cloud_ptr; pcl::PointCloud<pcl::PointWithViewpoint> far_ranges; Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ()); std::vector<int> pcd_filename_indices = pcl::console::parse_file_extension_argument (argc, argv, "pcd"); if (!pcd_filename_indices.empty ()) { std::string filename = argv[pcd_filename_indices[0]]; if (pcl::io::loadPCDFile (filename, point_cloud) == -1) { cerr << "Was not able to open file \""<<filename<<"\".\n"; printUsage (argv[0]); return 0; } scene_sensor_pose = Eigen::Affine3f (Eigen::Translation3f (point_cloud.sensor_origin_[0], point_cloud.sensor_origin_[1], point_cloud.sensor_origin_[2])) * Eigen::Affine3f (point_cloud.sensor_orientation_); std::string far_ranges_filename = pcl::getFilenameWithoutExtension (filename)+"_far_ranges.pcd"; if (pcl::io::loadPCDFile (far_ranges_filename.c_str (), far_ranges) == -1) std::cout << "Far ranges file \""<<far_ranges_filename<<"\" does not exists.\n"; } else { setUnseenToMaxRange = true; cout << "\nNo *.pcd file given => Genarating example point cloud.\n\n"; for (float x=-0.5f; x<=0.5f; x+=0.01f) { for (float y=-0.5f; y<=0.5f; y+=0.01f) { PointType point; point.x = x; point.y = y; point.z = 2.0f - y; point_cloud.points.push_back (point); } } point_cloud.width = (int) point_cloud.points.size (); point_cloud.height = 1; } // ----------------------------------------------- // -----Create RangeImage from the PointCloud----- // ----------------------------------------------- float noise_level = 0.0; float min_range = 0.0f; int border_size = 1; boost::shared_ptr<pcl::RangeImage> range_image_ptr (new pcl::RangeImage); pcl::RangeImage& range_image = *range_image_ptr; range_image.createFromPointCloud (point_cloud, angular_resolution, pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size); range_image.integrateFarRanges (far_ranges); if (setUnseenToMaxRange) range_image.setUnseenToMaxRange (); // -------------------------------------------- // -----Open 3D viewer and add point cloud----- // -------------------------------------------- pcl::visualization::PCLVisualizer viewer ("3D Viewer"); viewer.setBackgroundColor (1, 1, 1); pcl::visualization::PointCloudColorHandlerCustom<pcl::PointWithRange> range_image_color_handler (range_image_ptr, 0, 0, 0); viewer.addPointCloud (range_image_ptr, range_image_color_handler, "range image"); viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "range image"); //viewer.addCoordinateSystem (1.0f); //PointCloudColorHandlerCustom<PointType> point_cloud_color_handler (point_cloud_ptr, 150, 150, 150); //viewer.addPointCloud (point_cloud_ptr, point_cloud_color_handler, "original point cloud"); viewer.initCameraParameters (); setViewerPose (viewer, range_image.getTransformationToWorldSystem ()); // -------------------------- // -----Show range image----- // -------------------------- pcl::visualization::RangeImageVisualizer range_image_widget ("Range image"); range_image_widget.showRangeImage (range_image); // -------------------------------- // -----Extract NARF keypoints----- // -------------------------------- pcl::RangeImageBorderExtractor range_image_border_extractor; pcl::NarfKeypoint narf_keypoint_detector; narf_keypoint_detector.setRangeImageBorderExtractor (&range_image_border_extractor); narf_keypoint_detector.setRangeImage (&range_image); narf_keypoint_detector.getParameters ().support_size = support_size; pcl::PointCloud<int> keypoint_indices; narf_keypoint_detector.compute (keypoint_indices); std::cout << "Found "<<keypoint_indices.points.size ()<<" key points.\n"; // ---------------------------------------------- // -----Show keypoints in range image widget----- // ---------------------------------------------- //for (size_t i=0; i<keypoint_indices.points.size (); ++i) //range_image_widget.markPoint (keypoint_indices.points[i]%range_image.width, //keypoint_indices.points[i]/range_image.width); // ------------------------------------- // -----Show keypoints in 3D viewer----- // ------------------------------------- pcl::PointCloud<pcl::PointXYZ>::Ptr keypoints_ptr (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>& keypoints = *keypoints_ptr; keypoints.points.resize (keypoint_indices.points.size ()); for (size_t i=0; i<keypoint_indices.points.size (); ++i) keypoints.points[i].getVector3fMap () = range_image.points[keypoint_indices.points[i]].getVector3fMap (); pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> keypoints_color_handler (keypoints_ptr, 0, 255, 0); viewer.addPointCloud<pcl::PointXYZ> (keypoints_ptr, keypoints_color_handler, "keypoints"); viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 7, "keypoints"); // ------------------------------------------------------ // -----Extract NARF descriptors for interest points----- // ------------------------------------------------------ std::vector<int> keypoint_indices2; keypoint_indices2.resize (keypoint_indices.points.size ()); for (unsigned int i=0; i<keypoint_indices.size (); ++i) // This step is necessary to get the right vector type keypoint_indices2[i]=keypoint_indices.points[i]; pcl::NarfDescriptor narf_descriptor (&range_image, &keypoint_indices2); narf_descriptor.getParameters ().support_size = support_size; narf_descriptor.getParameters ().rotation_invariant = rotation_invariant; pcl::PointCloud<pcl::Narf36> narf_descriptors; narf_descriptor.compute (narf_descriptors); cout << "Extracted "<<narf_descriptors.size ()<<" descriptors for " <<keypoint_indices.points.size ()<< " keypoints.\n"; //-------------------- // -----Main loop----- //-------------------- while (!viewer.wasStopped ()) { range_image_widget.spinOnce (); // process GUI events viewer.spinOnce (); pcl_sleep(0.01); } }