jffLazyGridTest_saving.cc
Go to the documentation of this file.
00001 #include <ndt_map.h>
00002 // #include <oc_tree.h>
00003 #include <lazy_grid.h>
00004 // #include <cell_vector.h>
00005 #include <pointcloud_utils.h>
00006 
00007 // #include "ros/ros.h"
00008 #include "pcl/point_cloud.h"
00009 // #include "sensor_msgs/PointCloud2.h"
00010 #include "pcl/io/pcd_io.h"
00011 #include "pcl/features/feature.h"
00012 #include <cstdio>
00013 #include <cstring>
00014 
00015 // #include <opencv/cv.h>
00016 // #include <opencv/highgui.h>
00017 // #include <boost/shared_ptr.hpp>
00018 // #include <boost/thread/mutex.hpp>
00019 // #include <cv_bridge/CvBridge.h>
00020 // #include <cv_bridge/cv_bridge.h>
00021 // #include <sensor_msgs/Image.h>
00022 
00023 #include <Eigen/Eigen>
00024 
00025 using namespace std;
00026 
00027 int main (int argc, char** argv)
00028 {
00029     if(argc < 2)
00030     {
00031         cout << "[ USAGE ] jffSaveTest cloud\n";
00032         exit(1);
00033     }
00034 
00035     cout << "Started saveTest.\n";
00036 
00037     pcl::PointCloud<pcl::PointXYZ> cloud;
00038     char fname[] = "test_wrl.wrl";
00039 
00040     cloud = lslgeneric::readVRML<pcl::PointXYZ>(argv[1]);
00041 
00042     lslgeneric::NDTMap<pcl::PointXYZ> nd(new lslgeneric::LazyGrid<pcl::PointXYZ>(0.2));
00043 
00044     nd.loadPointCloud(cloud);
00045     nd.computeNDTCells();
00046 
00047     nd.writeToVRML(fname);
00048 
00049     if (nd.writeToJFF("LazyGrid.jff") < 0)
00050         cout << "writing to jff failed\n";
00051 
00052     cout << "Finished saveTest.\n";
00053 
00054     return 0;
00055 }
00056 


ndt_map
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Mon Jan 6 2014 11:31:57