00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage 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 the Willow Garage 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 #include <stdlib.h> 00036 00037 #include <vector> 00038 #include <iostream> 00039 00040 #include <point_cloud_mapping/kdtree/kdtree_ann.h> 00041 00042 // include all descriptors for you 00043 #include <ias_descriptors_3d/all_descriptors.h> 00044 00045 using namespace std; 00046 00047 void createPointCloud(sensor_msgs::PointCloud& data); 00048 00049 // -------------------------------------------------------------- 00053 // -------------------------------------------------------------- 00054 int main() 00055 { 00056 // ---------------------------------------------- 00057 // Read point cloud data and create Kd-tree that represents points. 00058 // We will compute features for all points in the point cloud. 00059 sensor_msgs::PointCloud data; 00060 createPointCloud(data); 00061 cloud_kdtree::KdTreeANN data_kdtree(data); 00062 std::vector<const geometry_msgs::Point32*> interest_pts; 00063 interest_pts.reserve(data.points.size()); 00064 //std::vector<const geometry_msgs::Point32*> interest_pts(data.points.size()); 00065 for (size_t i = 0 ; i < data.points.size() ; i++) 00066 { 00067 interest_pts.push_back(&(data.points[i])); 00068 } 00069 00070 // ---------------------------------------------- 00071 // SpectralAnalysis is not a descriptor, it is a class that holds 00072 // intermediate data to be used/shared by different descriptors. 00073 // It performs eigen-analyis of local neighborhoods and extracts 00074 // eigenvectors and values. Here, we set it to look at neighborhoods 00075 // within a radius of 5.0 around each interest point. 00076 SpectralAnalysis sa(5.0); 00077 00078 // ---------------------------------------------- 00079 // Examines the eigenvalues for a local neighborhood scatter matrix 00080 // to give features that represent the local shape (how flat, how linear, 00081 // how scattered) of the neighborhood. 00082 // This descriptor uses information from spectral analysis. 00083 // ShapeSpectral shape_spectral(sa); 00084 00085 // ---------------------------------------------- 00086 // Compute a spin image centered at each interest point. 00087 // The spin axis here is the +z direction (0,0,1). 00088 // The spin image resolution has 1.0 square cells. 00089 // Note that the number of rows in the spin image MUST be odd 00090 // (see documentation). 00091 // The last argument is used when computing spin image for 00092 // regions of points, since we are computing a descriptor 00093 // for single points it should be false. 00094 // SpinImageCustom spin_image1(0, 0, 1, 1.0, 1.0, 5, 4, false); 00095 00096 // ---------------------------------------------- 00097 // Compute another spin image centered at each interest point. 00098 // The spin axis here is about each interest points' estimated normal. 00099 // We can either recompute the normals using a different radius than 00100 // used with spectral_shape (by instantiating another SpectralAnalysis), 00101 // or we can use the same normals computed from shape_spectral. 00102 // SpinImageNormal spin_image2(1.0, 1.0, 5, 4, false, sa); 00103 00104 // ---------------------------------------------- 00105 // Compares the locally estimated normal and tangent vectors around 00106 // each interest point against the specified reference direction (+z). 00107 // The feature value is cos(theta), where theta is the angle between 00108 // the normal/tangent and the reference direction 00109 // OrientationNormal o_normal(0, 0, 1, sa); 00110 //OrientationTangent o_tangent(0, 0, 1, sa); 00111 00112 // ---------------------------------------------- 00113 // The feature is simply the z coordinate for each interest point 00114 // Position position; 00115 00116 // ---------------------------------------------- 00117 // Computes the bounding box in the principle component space 00118 // of all points within radius 6.0. That is, feature values 00119 // are the lengths of the box along the 3 component directions. 00120 BoundingBoxSpectral bbox_spectral(6.0, sa); 00121 00122 // ---------------------------------------------- 00123 // Put all descriptors into a vector 00124 vector<Descriptor3D*> descriptors_3d; 00125 // descriptors_3d.push_back(&shape_spectral); 00126 // descriptors_3d.push_back(&spin_image1); 00127 // descriptors_3d.push_back(&spin_image2); 00128 // descriptors_3d.push_back(&o_normal); 00129 // descriptors_3d.push_back(&o_tangent); 00130 // descriptors_3d.push_back(&position); 00131 descriptors_3d.push_back(&bbox_spectral); 00132 00133 // ---------------------------------------------- 00134 // Iterate over each descriptor and compute features for each point in the point cloud. 00135 // The compute() populates a vector of vector of floats, i.e. a feature vector for each 00136 // interest point. If the features couldn't be computed successfully for an interest point, 00137 // its feature vector has size 0 00138 unsigned int nbr_descriptors = descriptors_3d.size(); 00139 vector<std::vector<std::vector<float> > > all_descriptor_results(nbr_descriptors); 00140 for (unsigned int i = 0 ; i < nbr_descriptors ; i++) 00141 { 00142 descriptors_3d[i]->compute(data, data_kdtree, interest_pts, all_descriptor_results[i]); 00143 } 00144 00145 // // ---------------------------------------------- 00146 // // Print out the bounding box dimension features for the first point 0 00147 std::vector<float>& pt0_bbox_features = all_descriptor_results[0][0]; 00148 cout << "Bounding box features size: " << pt0_bbox_features.size() << endl; 00149 for (size_t i = 0 ; i < pt0_bbox_features.size() ; i++) 00150 { 00151 cout << " " << pt0_bbox_features[i]; 00152 } 00153 cout << endl; 00154 return 0; 00155 } 00156 00157 // Generates random point cloud 00158 void createPointCloud(sensor_msgs::PointCloud& data) 00159 { 00160 unsigned int nbr_pts = 5000; 00161 data.points.resize(nbr_pts); 00162 00163 for (unsigned int i = 0 ; i < nbr_pts ; i++) 00164 { 00165 data.points[i].x = rand() % 50; 00166 data.points[i].y = rand() % 50; 00167 data.points[i].z = rand() % 50; 00168 } 00169 } 00170