example_vosch.cpp
Go to the documentation of this file.
00001 #include "vosch/vosch_tools.h"
00002 
00003 //-------
00004 //* main
00005 int main( int argc, char** argv ){
00006   if( argc != 2 ){
00007     ROS_ERROR ("Need one parameter! Syntax is: %s {input_pointcloud_filename.pcd}\n", argv[0]);
00008     return(-1);
00009   }
00010   //* voxel size (downsample_leaf)
00011   const double voxel_size = 0.01;
00012 
00013   //* read
00014   pcl::PointCloud<pcl::PointXYZRGB> input_cloud;
00015   readPoints( argv[1], input_cloud );
00016   double t1 = my_clock();
00017 
00018   //* compute normals
00019   pcl::PointCloud<pcl::PointXYZRGBNormal> cloud;
00020   computeNormal( input_cloud, cloud );
00021   ROS_INFO("Normal compute done in %f seconds.", my_clock()-t1);
00022 
00023   //* voxelize
00024   pcl::VoxelGrid<pcl::PointXYZRGBNormal> grid;
00025   pcl::PointCloud<pcl::PointXYZRGBNormal> cloud_downsampled;
00026   getVoxelGrid( grid, cloud, cloud_downsampled, voxel_size );
00027 
00028   //* extract - VOSCH -
00029   std::vector<float> vosch;
00030   extractVOSCH( grid, cloud, cloud_downsampled, vosch, 127, 127, 127, voxel_size );
00031   //std::vector< std::vector<float> > vosch;
00032   //extractVOSCH( grid, cloud, cloud_downsampled, vosch, 127, 127, 127, voxel_size, 10, 5, 5, 5 );
00033 
00034   ROS_INFO("VOSCH %ld", input_cloud.points.size());
00035 
00036   //* write
00037   writeFeature( "vosch.pcd", vosch );
00038 
00039   return(0);
00040 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


vosch
Author(s): Asako Kanezaki
autogenerated on Sun Oct 6 2013 12:06:15