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