$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/range_image/range_image.h" 00045 #include "pcl/io/pcd_io.h" 00046 #include "pcl_visualization/range_image_visualizer.h" 00047 #include "pcl_visualization/pcl_visualizer.h" 00048 #include "pcl/features/range_image_border_extractor.h" 00049 #include "pcl/keypoints/narf_keypoint.h" 00050 #include "pcl/features/narf_descriptor.h" 00051 00052 using namespace pcl; 00053 using namespace pcl_visualization; 00054 typedef PointXYZ PointType; 00055 00056 // -------------------- 00057 // -----Parameters----- 00058 // -------------------- 00059 float angular_resolution = 0.5f; 00060 float support_size = 0.2f; 00061 RangeImage::CoordinateFrame coordinate_frame = RangeImage::CAMERA_FRAME; 00062 bool setUnseenToMaxRange = false, rotation_invariant=true; 00063 00064 // -------------- 00065 // -----Help----- 00066 // -------------- 00067 void printUsage(const char* progName) 00068 { 00069 cout << "\n\nUsage: "<<progName<<" [options] <scene.pcd>\n\n" 00070 << "Options:\n" 00071 << "-------------------------------------------\n" 00072 << "-r <float> angular resolution in degrees (default "<<angular_resolution<<")\n" 00073 << "-c <int> coordinate frame (default "<<(int)coordinate_frame<<")\n" 00074 << "-m Treat all unseen points to max range\n" 00075 << "-s <float> support size for the interest points (diameter of the used sphere in meters) (default "<<support_size<<")\n" 00076 << "-o <0/1> switch rotational invariant version of the feature on/off (default "<<(int)rotation_invariant<<")\n" 00077 << "-h this help\n" 00078 << "\n\n"; 00079 } 00080 00081 // -------------- 00082 // -----Main----- 00083 // -------------- 00084 int main (int argc, char** argv) 00085 { 00086 // -------------------------------------- 00087 // -----Parse Command Line Arguments----- 00088 // -------------------------------------- 00089 for (char c; (c = getopt(argc, argv, "r:c:ms:o:h")) != -1; ) { 00090 switch (c) { 00091 case 'r': 00092 { 00093 angular_resolution = strtod(optarg, NULL); 00094 cout << "Setting angular resolution to "<<angular_resolution<<".\n"; 00095 break; 00096 } 00097 case 'c': 00098 { 00099 coordinate_frame = (RangeImage::CoordinateFrame)strtol(optarg, NULL, 0); 00100 cout << "Using coordinate frame "<<(int)coordinate_frame<<".\n"; 00101 break; 00102 } 00103 case 'm': 00104 { 00105 setUnseenToMaxRange = true; 00106 break; 00107 } 00108 case 's': 00109 { 00110 support_size = strtod(optarg, NULL); 00111 cout << "Setting support size to "<<support_size<<".\n"; 00112 break; 00113 } 00114 case 'o': 00115 { 00116 rotation_invariant = strtod(optarg, NULL); 00117 cout << "Switching rotation invariant feature version "<<(rotation_invariant ? "on" : "off")<<".\n"; 00118 break; 00119 } 00120 case 'h': 00121 printUsage(argv[0]); 00122 exit(0); 00123 } 00124 } 00125 angular_resolution = deg2rad(angular_resolution); 00126 00127 // ------------------------------------------------------------------ 00128 // -----Read pcd file or create example point cloud if not given----- 00129 // ------------------------------------------------------------------ 00130 // Read/Generate point cloud 00131 pcl::PointCloud<PointType> point_cloud; 00132 PointCloud<PointWithViewpoint> far_ranges; 00133 Eigen::Affine3f scene_sensor_pose(Eigen::Affine3f::Identity()); 00134 if (optind < argc) 00135 { 00136 sensor_msgs::PointCloud2 point_cloud_data; 00137 if (pcl::io::loadPCDFile(argv[optind], point_cloud_data) == -1) 00138 { 00139 ROS_ERROR_STREAM("Was not able to open file \""<<argv[optind]<<"\".\n"); 00140 printUsage(argv[0]); 00141 exit(0); 00142 } 00143 fromROSMsg(point_cloud_data, point_cloud); 00144 RangeImage::extractFarRanges(point_cloud_data, far_ranges); 00145 if (pcl::getFieldIndex(point_cloud_data, "vp_x")>=0) 00146 { 00147 cout << "Scene point cloud has viewpoint information.\n"; 00148 PointCloud<PointWithViewpoint> tmp_pc; fromROSMsg(point_cloud_data, tmp_pc); 00149 Eigen::Vector3f average_viewpoint = RangeImage::getAverageViewPoint(tmp_pc); 00150 scene_sensor_pose = Eigen::Translation3f(average_viewpoint) * scene_sensor_pose; 00151 } 00152 } 00153 else 00154 { 00155 cout << "\nNo *.pcd file given => Genarating example point cloud.\n\n"; 00156 for (float x=-0.5f; x<=0.5f; x+=0.01f) 00157 { 00158 for (float y=-0.5f; y<=0.5f; y+=0.01f) 00159 { 00160 PointType point; point.x = x; point.y = y; point.z = 2.0f - y; 00161 point_cloud.points.push_back(point); 00162 } 00163 } 00164 point_cloud.width = point_cloud.points.size(); point_cloud.height = 1; 00165 } 00166 00167 00168 // ----------------------------------------------- 00169 // -----Create RangeImage from the PointCloud----- 00170 // ----------------------------------------------- 00171 float noise_level = 0.0; 00172 float min_range = 0.0f; 00173 int border_size = 1; 00174 RangeImage range_image; 00175 range_image.createFromPointCloud(point_cloud, angular_resolution, deg2rad(360.0f), deg2rad(180.0f), 00176 scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size); 00177 range_image.integrateFarRanges(far_ranges); 00178 if (setUnseenToMaxRange) 00179 range_image.setUnseenToMaxRange(); 00180 00181 // -------------------------------------------- 00182 // -----Open 3D viewer and add point cloud----- 00183 // -------------------------------------------- 00184 PCLVisualizer viewer("3D Viewer"); 00185 viewer.addCoordinateSystem(1.0f); 00186 viewer.addPointCloud(point_cloud, "original point cloud"); 00187 //viewer.addPointCloud(range_image, "range image"); 00188 00189 // -------------------------- 00190 // -----Show range image----- 00191 // -------------------------- 00192 RangeImageVisualizer range_image_widget("Range image"); 00193 range_image_widget.setRangeImage(range_image); 00194 00195 // -------------------------------- 00196 // -----Extract NARF keypoints----- 00197 // -------------------------------- 00198 RangeImageBorderExtractor range_image_border_extractor; 00199 NarfKeypoint narf_keypoint_detector; 00200 narf_keypoint_detector.setRangeImageBorderExtractor(&range_image_border_extractor); 00201 narf_keypoint_detector.setRangeImage(&range_image); 00202 narf_keypoint_detector.getParameters().support_size = support_size; 00203 00204 PointCloud<int> keypoint_indices; 00205 narf_keypoint_detector.compute(keypoint_indices); 00206 std::cout << "Found "<<keypoint_indices.points.size()<<" key points.\n"; 00207 00208 // ---------------------------------------------- 00209 // -----Show keypoints in range image widget----- 00210 // ---------------------------------------------- 00211 for (size_t i=0; i<keypoint_indices.points.size(); ++i) 00212 range_image_widget.markPoint(keypoint_indices.points[i]%range_image.width, keypoint_indices.points[i]/range_image.width); 00213 00214 // ------------------------------------- 00215 // -----Show keypoints in 3D viewer----- 00216 // ------------------------------------- 00217 PointCloud<PointXYZ> keypoints; 00218 keypoints.points.resize(keypoint_indices.points.size()); 00219 for (size_t i=0; i<keypoint_indices.points.size(); ++i) 00220 keypoints.points[i].getVector3fMap() = range_image.points[keypoint_indices.points[i]].getVector3fMap(); 00221 viewer.addPointCloud(keypoints, "keypoints"); 00222 viewer.setPointCloudRenderingProperties(pcl_visualization::PCL_VISUALIZER_POINT_SIZE, 7, "keypoints"); 00223 00224 // ------------------------------------------------------ 00225 // -----Extract NARF descriptors for interest points----- 00226 // ------------------------------------------------------ 00227 vector<int> keypoint_indices2; 00228 keypoint_indices2.resize(keypoint_indices.points.size()); 00229 for (unsigned int i=0; i<keypoint_indices.size(); ++i) // This step is necessary to get the right vector type 00230 keypoint_indices2[i]=keypoint_indices.points[i]; 00231 NarfDescriptor narf_descriptor(&range_image, &keypoint_indices2); 00232 narf_descriptor.getParameters().support_size = support_size; 00233 narf_descriptor.getParameters().rotation_invariant = rotation_invariant; 00234 PointCloud<Narf36> narf_descriptors; 00235 narf_descriptor.compute(narf_descriptors); 00236 cout << "Extracted "<<narf_descriptors.size()<<" descriptors for "<<keypoint_indices.points.size()<< " keypoints.\n"; 00237 00238 //-------------------- 00239 // -----Main loop----- 00240 //-------------------- 00241 while(!viewer.wasStopped() || range_image_widget.isShown()) 00242 { 00243 ImageWidgetWX::spinOnce(); // process GUI events 00244 viewer.spinOnce(100); 00245 usleep(100000); 00246 } 00247 }