$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_visualization/range_image_visualizer.h" 00045 00046 #include <Eigen/Geometry> 00047 #include "pcl/point_cloud.h" 00048 #include "pcl/point_types.h" 00049 #include "pcl/io/pcd_io.h" 00050 #include "pcl/range_image/range_image.h" 00051 00052 using namespace pcl; 00053 00054 typedef PointWithViewpoint PointType; 00055 00056 int 00057 main (int argc, char** argv) 00058 { 00059 pcl::PointCloud<PointType> point_cloud; 00060 00061 bool use_point_cloud_from_file = argc >= 2; 00062 if (use_point_cloud_from_file) { 00063 string fileName = argv[1]; 00064 ROS_INFO_STREAM ("Trying to open \""<<fileName<<"\".\n"); 00065 if (pcl::io::loadPCDFile(fileName, point_cloud) == -1) { 00066 ROS_ERROR_STREAM("Was not able to open file \""<<fileName<<"\".\n"); 00067 use_point_cloud_from_file = false; 00068 } 00069 } 00070 else { 00071 cout << "\n\nUsage: "<<argv[0]<<" <file.pcl> <angular resolution (default 0.5)> <coordinate frame (default 0)>\n\n"; 00072 } 00073 00074 if (!use_point_cloud_from_file) { 00075 ROS_INFO_STREAM ("No file given or could not read file => Genarating example point cloud.\n"); 00076 for (float y=-0.5f; y<=0.5f; y+=0.01f) { 00077 for (float z=-0.5f; z<=0.5f; z+=0.01f) { 00078 PointType point; 00079 point.x = 2.0f - y; 00080 point.y = y; 00081 point.z = z; 00082 point_cloud.points.push_back(point); 00083 } 00084 } 00085 point_cloud.width = point_cloud.points.size(); 00086 point_cloud.height = 1; 00087 } 00088 00089 float angular_resolution = DEG2RAD(0.5f); 00090 if (argc >= 3) { 00091 float tmp_angular_resolution = strtod(argv[2], NULL); 00092 if (tmp_angular_resolution >= 0.1f) // Check for too small numbers (or we might get a memory problem) 00093 { 00094 cout << "Using angular resolution "<<tmp_angular_resolution<<"deg from command line.\n"; 00095 angular_resolution = DEG2RAD(tmp_angular_resolution); 00096 } 00097 } 00098 00099 RangeImage::CoordinateFrame coordinate_frame = RangeImage::CAMERA_FRAME; 00100 if (argc >= 4) 00101 { 00102 coordinate_frame = (RangeImage::CoordinateFrame)strtol(argv[3], NULL, 0); 00103 cout << "Using coordinate frame "<<coordinate_frame<<".\n"; 00104 } 00105 00106 // We now want to create a range image from the above point cloud, with a 1° angular resolution 00107 float max_angle_width = DEG2RAD(360.0f); // 360.0 degree in radians 00108 float max_angle_height = DEG2RAD(180.0f); // 180.0 degree in radians 00109 float noise_level=0.0f; 00110 float min_range = 0.0f; 00111 int border_size = 2; 00112 00113 RangeImage range_image; 00114 //Eigen::Transform3f sensor_pose = (Eigen::Transform3f)Eigen::Translation3f(0.0f, 0.0f, 0.0f); 00115 //range_image.createFromPointCloud(point_cloud, angular_resolution, max_angle_width, max_angle_height, sensor_pose, coordinate_frame, 00116 //noise_level, min_range, border_size); 00117 range_image.createFromPointCloudWithViewpoints(point_cloud, angular_resolution, max_angle_width, max_angle_height, 00118 coordinate_frame, noise_level, min_range, border_size); 00119 00120 cout << PVARN(range_image); 00121 00122 pcl_visualization::RangeImageVisualizer range_image_widget ("Range Image"); 00123 range_image_widget.setRangeImage (range_image); 00124 //range_image_widget.markPoint (range_image.width/2, range_image.height/2, wxRED_PEN); 00125 //range_image_widget.markLine (0.0f, 0.0f, range_image.width/2, range_image.height/2, wxRED_PEN); 00126 00127 pcl_visualization::RangeImageVisualizer::spin (); // process GUI events 00128 00129 // OR, if you want your own main loop instead: 00130 //while(range_imageWidget.isShown()) { 00131 //RangeImageVisualizer::spinOnce(); // process GUI events 00132 //usleep(10000); 00133 //} 00134 00135 wxEntryCleanup(); // Free memory allocated by wxEntryStart 00136 00137 return (0); 00138 } 00139 00140 /* ]--- */