00001
00002
00003 #include <iostream>
00004
00005 #include <boost/thread/thread.hpp>
00006 #include <pcl/point_cloud.h>
00007 #include <pcl/io/pcd_io.h>
00008 #include <pcl/visualization/range_image_visualizer.h>
00009 #include <pcl/range_image/range_image.h>
00010 #include <pcl/features/narf.h>
00011 #include <pcl/console/parse.h>
00012
00013 float angular_resolution = 0.5f;
00014 int rotation_invariant = 0;
00015 float support_size = 0.3f;
00016 int descriptor_size = 36;
00017 pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
00018 bool setUnseenToMaxRange = false;
00019
00020 typedef pcl::PointXYZ PointType;
00021
00022 void
00023 printUsage (const char* progName)
00024 {
00025 std::cout << "\n\nUsage: "<<progName<<" [options] <scene.pcd>\n\n"
00026 << "Options:\n"
00027 << "-------------------------------------------\n"
00028 << "-r <float> angular resolution in degrees (default "<<angular_resolution<<")\n"
00029 << "-s <float> support size for the interest points (diameter of the used sphere - "
00030 << "default "<<support_size<<")\n"
00031 << "-d <int> descriptor size (default "<<descriptor_size<<")\n"
00032 << "-c <int> coordinate frame of the input point cloud (default "<< (int)coordinate_frame<<")\n"
00033 << "-o <0/1> switch rotational invariant version of the feature on/off"
00034 << " (default "<< (int)rotation_invariant<<")\n"
00035 << "-m set unseen pixels to max range\n"
00036 << "-h this help\n"
00037 << "\n\n";
00038 }
00039
00040 int
00041 main (int argc, char** argv)
00042 {
00043
00044
00045
00046 if (pcl::console::find_argument (argc, argv, "-h") >= 0)
00047 {
00048 printUsage (argv[0]);
00049 return 0;
00050 }
00051 if (pcl::console::find_argument (argc, argv, "-m") >= 0)
00052 {
00053 setUnseenToMaxRange = true;
00054 std::cout << "Setting unseen values in range image to maximum range readings.\n";
00055 }
00056 if (pcl::console::parse (argc, argv, "-o", rotation_invariant) >= 0)
00057 std::cout << "Switching rotation invariant feature version "<< (rotation_invariant ? "on" : "off")<<".\n";
00058 int tmp_coordinate_frame;
00059 if (pcl::console::parse (argc, argv, "-c", tmp_coordinate_frame) >= 0)
00060 {
00061 coordinate_frame = pcl::RangeImage::CoordinateFrame (tmp_coordinate_frame);
00062 std::cout << "Using coordinate frame "<< (int)coordinate_frame<<".\n";
00063 }
00064 if (pcl::console::parse (argc, argv, "-s", support_size) >= 0)
00065 std::cout << "Setting support size to "<<support_size<<".\n";
00066 if (pcl::console::parse (argc, argv, "-d", descriptor_size) >= 0)
00067 std::cout << "Setting descriptor size to "<<descriptor_size<<".\n";
00068 if (pcl::console::parse (argc, argv, "-r", angular_resolution) >= 0)
00069 std::cout << "Setting angular resolution to "<<angular_resolution<<"deg.\n";
00070 angular_resolution = pcl::deg2rad (angular_resolution);
00071
00072
00073
00074
00075
00076 pcl::PointCloud<PointType>::Ptr point_cloud_ptr (new pcl::PointCloud<PointType>);
00077 pcl::PointCloud<PointType>& point_cloud = *point_cloud_ptr;
00078 pcl::PointCloud<pcl::PointWithViewpoint> far_ranges;
00079 Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ());
00080 std::vector<int> pcd_filename_indices = pcl::console::parse_file_extension_argument (argc, argv, "pcd");
00081 if (!pcd_filename_indices.empty ())
00082 {
00083 std::string filename = argv[pcd_filename_indices[0]];
00084 if (pcl::io::loadPCDFile (filename, point_cloud) == -1)
00085 {
00086 std::cout << "Was not able to open file \""<<filename<<"\".\n";
00087 printUsage (argv[0]);
00088 return 0;
00089 }
00090 scene_sensor_pose = Eigen::Affine3f (Eigen::Translation3f (point_cloud.sensor_origin_[0],
00091 point_cloud.sensor_origin_[1],
00092 point_cloud.sensor_origin_[2])) *
00093 Eigen::Affine3f (point_cloud.sensor_orientation_);
00094 std::string far_ranges_filename = pcl::getFilenameWithoutExtension (filename)+"_far_ranges.pcd";
00095 if (pcl::io::loadPCDFile (far_ranges_filename.c_str (), far_ranges) == -1)
00096 std::cout << "Far ranges file \""<<far_ranges_filename<<"\" does not exists.\n";
00097 }
00098 else
00099 {
00100 std::cout << "\nNo *.pcd file for scene given.\n\n";
00101 printUsage (argv[0]);
00102 return 1;
00103 }
00104
00105
00106
00107
00108 float noise_level = 0.0;
00109 float min_range = 0.0f;
00110 int border_size = 1;
00111 boost::shared_ptr<pcl::RangeImage> range_image_ptr (new pcl::RangeImage);
00112 pcl::RangeImage& range_image = *range_image_ptr;
00113 range_image.createFromPointCloud (point_cloud, angular_resolution, pcl::deg2rad (360.0f), pcl::deg2rad (180.0f),
00114 scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size);
00115 range_image.integrateFarRanges (far_ranges);
00116 if (setUnseenToMaxRange)
00117 range_image.setUnseenToMaxRange ();
00118
00119
00120 std::cout << "Now extracting NARFs in every image point.\n";
00121 std::vector<std::vector<pcl::Narf*> > narfs;
00122 narfs.resize (range_image.points.size ());
00123 int last_percentage=-1;
00124 for (unsigned int y=0; y<range_image.height; ++y)
00125 {
00126 for (unsigned int x=0; x<range_image.width; ++x)
00127 {
00128 int index = y*range_image.width+x;
00129 int percentage = (int) ((100*index) / range_image.points.size ());
00130 if (percentage > last_percentage)
00131 {
00132 std::cout << percentage<<"% "<<std::flush;
00133 last_percentage = percentage;
00134 }
00135 pcl::Narf::extractFromRangeImageAndAddToList (range_image, x, y, descriptor_size,
00136 support_size, rotation_invariant != 0, narfs[index]);
00137
00138 }
00139 }
00140 std::cout << "100%\n";
00141 std::cout << "Done.\n\n Now you can click on points in the image to visualize how the descriptor is "
00142 << "extracted and see the descriptor distances to every other point..\n";
00143
00144
00145
00146
00147 pcl::visualization::RangeImageVisualizer range_image_widget ("Scene range image"),
00148 surface_patch_widget("Descriptor's surface patch"),
00149 descriptor_widget("Descriptor"),
00150 descriptor_distances_widget("descriptor distances");
00151 range_image_widget.showRangeImage (range_image);
00152
00153
00154
00155
00156
00157 while (true)
00158 {
00159 range_image_widget.spinOnce ();
00160 surface_patch_widget.spinOnce ();
00161 descriptor_widget.spinOnce ();
00162 pcl_sleep(0.01);
00163
00164
00165 continue;
00166
00167
00168
00169 int clicked_pixel_x, clicked_pixel_y;
00170
00171 if (!range_image.isValid (clicked_pixel_x, clicked_pixel_y))
00172 continue;
00173
00174
00175
00176
00177
00178
00179 int selected_index = clicked_pixel_y*range_image.width + clicked_pixel_x;
00180 pcl::Narf narf;
00181 if (!narf.extractFromRangeImage (range_image, clicked_pixel_x, clicked_pixel_y,
00182 descriptor_size, support_size))
00183 {
00184 continue;
00185 }
00186
00187 int surface_patch_pixel_size = narf.getSurfacePatchPixelSize ();
00188 float surface_patch_world_size = narf.getSurfacePatchWorldSize ();
00189 surface_patch_widget.showFloatImage (narf.getSurfacePatch (), surface_patch_pixel_size, surface_patch_pixel_size,
00190 -0.5f*surface_patch_world_size, 0.5f*surface_patch_world_size, true);
00191 float surface_patch_rotation = narf.getSurfacePatchRotation ();
00192 float patch_middle = 0.5f* (float (surface_patch_pixel_size-1));
00193 float angle_step_size = pcl::deg2rad (360.0f)/narf.getDescriptorSize ();
00194 float cell_size = surface_patch_world_size/float (surface_patch_pixel_size),
00195 cell_factor = 1.0f/cell_size,
00196 max_dist = 0.5f*surface_patch_world_size,
00197 line_length = cell_factor* (max_dist-0.5f*cell_size);
00198 for (int descriptor_value_idx=0; descriptor_value_idx<narf.getDescriptorSize (); ++descriptor_value_idx)
00199 {
00200 float angle = descriptor_value_idx*angle_step_size + surface_patch_rotation;
00201
00202
00203 }
00204 std::vector<float> rotations, strengths;
00205 narf.getRotations (rotations, strengths);
00206 float radius = 0.5f*surface_patch_pixel_size;
00207 for (unsigned int i=0; i<rotations.size (); ++i)
00208 {
00209
00210
00211 }
00212
00213 descriptor_widget.showFloatImage (narf.getDescriptor (), narf.getDescriptorSize (), 1, -0.1f, 0.3f, true);
00214
00215
00216
00217
00218 const std::vector<pcl::Narf*>& narfs_of_selected_point = narfs[selected_index];
00219 if (narfs_of_selected_point.empty ())
00220 continue;
00221
00222
00223 float* descriptor_distance_image = new float[range_image.points.size ()];
00224 for (unsigned int point_index=0; point_index<range_image.points.size (); ++point_index)
00225 {
00226 float& descriptor_distance = descriptor_distance_image[point_index];
00227 descriptor_distance = std::numeric_limits<float>::infinity ();
00228 std::vector<pcl::Narf*>& narfs_of_current_point = narfs[point_index];
00229 if (narfs_of_current_point.empty ())
00230 continue;
00231 for (unsigned int i=0; i<narfs_of_selected_point.size (); ++i)
00232 {
00233 for (unsigned int j=0; j<narfs_of_current_point.size (); ++j)
00234 {
00235 descriptor_distance = (std::min)(descriptor_distance,
00236 narfs_of_selected_point[i]->getDescriptorDistance (*narfs_of_current_point[j]));
00237 }
00238 }
00239 }
00240 descriptor_distances_widget.showFloatImage (descriptor_distance_image, range_image.width, range_image.height,
00241 -std::numeric_limits<float>::infinity (), std::numeric_limits<float>::infinity (), true);
00242 delete[] descriptor_distance_image;
00243 }
00244 }