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