example_spin_images.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Point Cloud Library (PCL) - www.pointclouds.org
00005  * Copyright (c) 2009-2011, Willow Garage, Inc.
00006  *
00007  * All rights reserved.
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions
00011  * are met:
00012  *
00013  * * Redistributions of source code must retain the above copyright
00014  *   notice, this list of conditions and the following disclaimer.
00015  * * Redistributions in binary form must reproduce the above
00016  *   copyright notice, this list of conditions and the following
00017  *   disclaimer in the documentation and/or other materials provided
00018  *   with the distribution.
00019  * * Neither the name of Willow Garage, Inc. nor the names of its
00020  *   contributors may be used to endorse or promote products derived
00021  *   from this software without specific prior written permission.
00022  *
00023  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  * POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
00037  *
00038  */
00039 
00040 
00041 
00042 #include <iostream>
00043 #include <vector>
00044 
00045 #include <pcl/io/pcd_io.h>
00046 #include <pcl/point_types.h>
00047 #include <pcl/features/normal_3d.h>
00048 #include <pcl/features/spin_image.h>
00049 
00050 int
00051 main (int, char** argv)
00052 {
00053   std::string filename = argv[1];
00054   std::cout << "Reading " << filename << std::endl;
00055   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00056 
00057   if (pcl::io::loadPCDFile <pcl::PointXYZ> (filename.c_str (), *cloud) == -1)
00058   // load the file
00059   {
00060     PCL_ERROR ("Couldn't read file");
00061     return (-1);
00062   }
00063   std::cout << "Loaded " << cloud->points.size () << " points." << std::endl;
00064 
00065   // Compute the normals
00066   pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normal_estimation;
00067   normal_estimation.setInputCloud (cloud);
00068 
00069   pcl::search::KdTree<pcl::PointXYZ>::Ptr kdtree (new pcl::search::KdTree<pcl::PointXYZ>);
00070   normal_estimation.setSearchMethod (kdtree);
00071 
00072   pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud< pcl::Normal>);
00073   normal_estimation.setRadiusSearch (0.03);
00074   normal_estimation.compute (*normals);
00075 
00076   // Setup spin image computation
00077   pcl::SpinImageEstimation<pcl::PointXYZ, pcl::Normal, pcl::Histogram<153> > spin_image_descriptor(8, 0.5, 16);
00078   spin_image_descriptor.setInputCloud (cloud);
00079   spin_image_descriptor.setInputNormals (normals);
00080 
00081   // Use the same KdTree from the normal estimation
00082   spin_image_descriptor.setSearchMethod (kdtree);
00083   pcl::PointCloud<pcl::Histogram<153> >::Ptr spin_images (new pcl::PointCloud<pcl::Histogram<153> >);
00084   spin_image_descriptor.setRadiusSearch (0.2);
00085 
00086   // Actually compute the spin images
00087   spin_image_descriptor.compute (*spin_images);
00088   std::cout << "SI output points.size (): " << spin_images->points.size () << std::endl;
00089 
00090   // Display and retrieve the spin image descriptor vector for the first point.
00091   pcl::Histogram<153> first_descriptor = spin_images->points[0];
00092   std::cout << first_descriptor << std::endl;
00093 
00094   return 0;
00095 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:23:36