$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 */ 00035 00036 /* \author Bastian Steder */ 00037 00038 /* ---[ */ 00039 00040 00041 #include <iostream> 00042 using namespace std; 00043 00044 #include "pcl/point_cloud.h" 00045 #include "pcl/io/pcd_io.h" 00046 #include "pcl_visualization/range_image_visualizer.h" 00047 #include "pcl/range_image/range_image.h" 00048 #include <pcl/features/narf.h> 00049 //#include "pcl/point_types.h" 00050 //#include <pcl/object_recognition/object_model_list.h> 00051 //#include <pcl/object_recognition/false_positives_filter.h> 00052 //#include <pcl/features/point_correspondences.h> 00053 //#include <pcl/features/pose_estimation_from_correspondences.h> 00054 //#include <pcl/features/range_image_border_extractor.h> 00055 //#include <interest_points/range_image_interest_point_detector.h> 00056 //#include <pcl/common/common_headers.h> 00057 00058 using namespace Eigen; 00059 using namespace pcl; 00060 using namespace pcl_visualization; 00061 00062 float angular_resolution = 0.5f; 00063 int use_rotation_invariance = 1; 00064 float support_size = 0.3f; 00065 int descriptor_size = 36; 00066 RangeImage::CoordinateFrame coordinate_frame = RangeImage::CAMERA_FRAME; 00067 bool setUnseenToMaxRange = false; 00068 00069 typedef PointXYZ PointType; 00070 00071 void printUsage(const char* progName) 00072 { 00073 cout << "\n\nUsage: "<<progName<<" [options] <scene.pcd>\n\n" 00074 << "Options:\n" 00075 << "-------------------------------------------\n" 00076 << "-r <float> angular resolution in degrees (default "<<angular_resolution<<")\n" 00077 << "-s <float> support size (diameter of the inclosed sphere) of the features in meters (default "<<support_size<<")\n" 00078 << "-d <int> descriptor size (default "<<descriptor_size<<")\n" 00079 << "-c <int> coordinate frame of the input point cloud (default "<<(int)coordinate_frame<<")\n" 00080 << "-i <0/1> use rotation invariant descriptor (default "<<use_rotation_invariance<<")\n" 00081 << "-m set unseen pixels to max range\n" 00082 << "-h this help\n" 00083 << "\n\n"; 00084 } 00085 00086 int main (int argc, char** argv) 00087 { 00088 // -------------------------------------- 00089 // -----Parse Command Line Arguments----- 00090 // -------------------------------------- 00091 for (char c; (c = getopt(argc, argv, "r:s:d:c:i:mh")) != -1; ) { 00092 switch (c) { 00093 case 'r': 00094 { 00095 angular_resolution = strtod(optarg, NULL); 00096 cout << PVARN(angular_resolution); 00097 break; 00098 } 00099 case 's': 00100 { 00101 support_size = strtod(optarg, NULL); 00102 cout << PVARN(support_size); 00103 break; 00104 } 00105 case 'c': 00106 { 00107 coordinate_frame = (RangeImage::CoordinateFrame)strtol(optarg, NULL, 0); 00108 cout << "Using coordinate frame "<<coordinate_frame<<".\n"; 00109 break; 00110 } 00111 case 'i': 00112 { 00113 use_rotation_invariance = (RangeImage::CoordinateFrame)strtol(optarg, NULL, 0); 00114 cout << (use_rotation_invariance ? "U":"Not u")<<"sing rotational invariant descriptor.\n"; 00115 break; 00116 } 00117 case 'm': 00118 { 00119 setUnseenToMaxRange = true; 00120 cout << "Unseen pixels will be considered max ranges.\n"; 00121 break; 00122 } 00123 case 'h': 00124 { 00125 printUsage(argv[0]); 00126 exit(0); 00127 } 00128 } 00129 } 00130 angular_resolution = deg2rad(angular_resolution); 00131 // -------------------------------------- 00132 00133 PointCloud<PointType> point_cloud; 00134 PointCloud<PointWithViewpoint> far_ranges; 00135 00136 // ----------------------- 00137 // -----Read pcd file----- 00138 // ----------------------- 00139 Eigen::Affine3f scene_sensor_pose(Eigen::Affine3f::Identity()); 00140 if (optind < argc) 00141 { 00142 sensor_msgs::PointCloud2 point_cloud_data; 00143 if (pcl::io::loadPCDFile(argv[optind], point_cloud_data) == -1) 00144 { 00145 ROS_ERROR_STREAM("Was not able to open file \""<<argv[optind]<<"\".\n"); 00146 printUsage(argv[0]); 00147 exit(0); 00148 } 00149 fromROSMsg(point_cloud_data, point_cloud); 00150 RangeImage::extractFarRanges(point_cloud_data, far_ranges); 00151 if (pcl::getFieldIndex(point_cloud_data, "vp_x")>=0) 00152 { 00153 //cout << "Scene point cloud has viewpoint information.\n"; 00154 PointCloud<PointWithViewpoint> tmp_pc; fromROSMsg(point_cloud_data, tmp_pc); 00155 Eigen::Vector3f average_viewpoint = RangeImage::getAverageViewPoint(tmp_pc); 00156 scene_sensor_pose = Eigen::Translation3f(average_viewpoint) * scene_sensor_pose; 00157 } 00158 } 00159 else 00160 { 00161 cout << "\nNo *.pcd file for scene given.\n\n"; 00162 printUsage(argv[0]); 00163 exit(0); 00164 } 00165 // ------------------------------------------------------------------ 00166 00167 // Create a range image from the above point cloud 00168 float noise_level = 0.25*support_size; 00169 RangeImage scene_range_image; 00170 scene_range_image.createFromPointCloud(point_cloud, angular_resolution, deg2rad(360.0f), deg2rad(180.0f), scene_sensor_pose, 00171 coordinate_frame, noise_level, 0.0f, 0); 00172 //cout << PVARN(scene_range_image); 00173 00174 // Extract NARF features: 00175 cout << "Now extracting NARFs in every image point.\n"; 00176 vector<vector<Narf*> > narfs; 00177 narfs.resize(scene_range_image.points.size()); 00178 int last_percentage=-1; 00179 for (unsigned int y=0; y<scene_range_image.height; ++y) 00180 { 00181 for (unsigned int x=0; x<scene_range_image.width; ++x) 00182 { 00183 int index = y*scene_range_image.width+x; 00184 int percentage = (100*index) / scene_range_image.points.size(); 00185 if (percentage > last_percentage) 00186 { 00187 cout << percentage<<"% "<<std::flush; 00188 last_percentage = percentage; 00189 } 00190 Narf::extractFromRangeImageAndAddToList(scene_range_image, x, y, descriptor_size, support_size, use_rotation_invariance, narfs[index]); 00191 //cout << "Extracted "<<narfs[index].size()<<" features for pixel "<<x<<","<<y<<".\n"; 00192 } 00193 } 00194 cout << "100%\n"; 00195 cout << "Done.\n\n Now you can click on points in the image to visualize how the descriptor is extracted and see the descriptor distances to every other point..\n"; 00196 00197 //--------------------- 00198 // -----Show image----- 00199 // -------------------- 00200 RangeImageVisualizer scene_range_image_widget("Scene range image"); 00201 scene_range_image_widget.setRangeImage(scene_range_image); 00202 scene_range_image_widget.visualize_selected_point = true; 00203 00204 //-------------------- 00205 // -----Main loop----- 00206 //-------------------- 00207 while(scene_range_image_widget.isShown()) { 00208 ImageWidgetWX::spinOnce(); // process GUI events 00209 usleep(100000); 00210 00211 if (!scene_range_image_widget.mouse_click_happened) 00212 continue; 00213 scene_range_image_widget.mouse_click_happened = false; 00214 float clicked_pixel_x_f = scene_range_image_widget.last_clicked_point_x, 00215 clicked_pixel_y_f = scene_range_image_widget.last_clicked_point_y; 00216 int clicked_pixel_x, clicked_pixel_y; 00217 scene_range_image.real2DToInt2D(clicked_pixel_x_f, clicked_pixel_y_f, clicked_pixel_x, clicked_pixel_y); 00218 if (!scene_range_image.isValid(clicked_pixel_x, clicked_pixel_y)) 00219 continue; 00220 //Vector3f clicked_3d_point; 00221 //scene_range_image.getPoint(clicked_pixel_x, clicked_pixel_y, clicked_3d_point); 00222 00223 static ImageWidgetWX surface_patch_widget, descriptor_widget; 00224 surface_patch_widget.show(false); 00225 descriptor_widget.show(false); 00226 00227 int selected_index = clicked_pixel_y*scene_range_image.width + clicked_pixel_x; 00228 Narf narf; 00229 if (!narf.extractFromRangeImage(scene_range_image, clicked_pixel_x, clicked_pixel_y, 00230 descriptor_size, support_size)) 00231 { 00232 continue; 00233 } 00234 00235 int surface_patch_pixel_size = narf.getSurfacePatchPixelSize(); 00236 float surface_patch_world_size = narf.getSurfacePatchWorldSize(); 00237 surface_patch_widget.setFloatImage(narf.getSurfacePatch(), surface_patch_pixel_size, surface_patch_pixel_size, 00238 "Descriptor's surface patch", -0.5f*surface_patch_world_size, 0.5f*surface_patch_world_size, true); 00239 float surface_patch_rotation = narf.getSurfacePatchRotation(); 00240 float patch_middle = 0.5f*(float(surface_patch_pixel_size-1)); 00241 float angle_step_size = deg2rad(360.0f)/narf.getDescriptorSize(); 00242 float cell_size = surface_patch_world_size/float(surface_patch_pixel_size), 00243 cell_factor = 1.0f/cell_size, 00244 max_dist = 0.5f*surface_patch_world_size, 00245 line_length = cell_factor*(max_dist-0.5f*cell_size); 00246 for (int descriptor_value_idx=0; descriptor_value_idx<narf.getDescriptorSize(); ++descriptor_value_idx) 00247 { 00248 float angle = descriptor_value_idx*angle_step_size + surface_patch_rotation; 00249 surface_patch_widget.markLine(patch_middle, patch_middle, patch_middle+line_length*sinf(angle), patch_middle+line_length*-cosf(angle)); 00250 } 00251 vector<float> rotations, strengths; 00252 narf.getRotations(rotations, strengths); 00253 float radius = 0.5f*surface_patch_pixel_size; 00254 for (unsigned int i=0; i<rotations.size(); ++i) 00255 { 00256 surface_patch_widget.markLine(radius-0.5, radius-0.5, radius-0.5f + 2.0f*radius*sinf(rotations[i]), 00257 radius-0.5f - 2.0f*radius*cosf(rotations[i]), wxRED_PEN); 00258 } 00259 00260 descriptor_widget.setFloatImage(narf.getDescriptor(), narf.getDescriptorSize(), 1, "Descriptor", -0.1f, 0.3f, true); 00261 00262 //=================================== 00263 //=====Compare with all features===== 00264 //=================================== 00265 const vector<Narf*>& narfs_of_selected_point = narfs[selected_index]; 00266 if (narfs_of_selected_point.empty()) 00267 continue; 00268 00269 static ImageWidgetWX descriptor_distances_widget; 00270 descriptor_distances_widget.show(false); 00271 float* descriptor_distance_image = new float[scene_range_image.points.size()]; 00272 for (unsigned int point_index=0; point_index<scene_range_image.points.size(); ++point_index) 00273 { 00274 float& descriptor_distance = descriptor_distance_image[point_index]; 00275 descriptor_distance = INFINITY; 00276 vector<Narf*>& narfs_of_current_point = narfs[point_index]; 00277 if (narfs_of_current_point.empty()) 00278 continue; 00279 for (unsigned int i=0; i<narfs_of_selected_point.size(); ++i) 00280 { 00281 for (unsigned int j=0; j<narfs_of_current_point.size(); ++j) 00282 { 00283 descriptor_distance = min(descriptor_distance, narfs_of_selected_point[i]->getDescriptorDistance(*narfs_of_current_point[j])); 00284 } 00285 } 00286 } 00287 descriptor_distances_widget.setFloatImage(descriptor_distance_image, scene_range_image.width, scene_range_image.height, "descriptor distances", -INFINITY, INFINITY, true); 00288 delete[] descriptor_distance_image; 00289 } 00290 }