00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 
00042 
00043 
00044 
00045 #include <pcl/recognition/ransac_based/obj_rec_ransac.h>
00046 #include <pcl/visualization/pcl_visualizer.h>
00047 #include <pcl/console/print.h>
00048 #include <pcl/console/parse.h>
00049 #include <pcl/io/pcd_io.h>
00050 #include <pcl/point_cloud.h>
00051 #include <vtkPolyDataReader.h>
00052 #include <vtkDoubleArray.h>
00053 #include <vtkDataArray.h>
00054 #include <vtkPointData.h>
00055 #include <vtkHedgeHog.h>
00056 #include <cstdio>
00057 #include <vector>
00058 
00059 using namespace std;
00060 using namespace pcl;
00061 using namespace io;
00062 using namespace console;
00063 using namespace recognition;
00064 using namespace visualization;
00065 
00066 #define _SHOW_MODEL_OCTREE_POINTS_
00067 
00068 
00069 void run (float pair_width, float voxel_size, float max_coplanarity_angle);
00070 void showModelOpps (PCLVisualizer& viz, const ModelLibrary::HashTable& hash_table, const ModelLibrary::Model* model, float pair_width);
00071 bool vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>& pcl_normals);
00072 
00073 
00074 
00075 int
00076 main (int argc, char** argv)
00077 {
00078   printf ("\nUsage: ./pcl_obj_rec_ransac_model_opps <pair_width> <voxel_size> <max_coplanarity_angle>\n\n");
00079 
00080   const int num_params = 3;
00081   float parameters[num_params] = {10.0f, 5.0f, 5.0f};
00082   string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"};
00083 
00084   
00085   for ( int i = 0 ; i < argc-1 && i < num_params ; ++i )
00086   {
00087     parameters[i] = static_cast<float> (atof (argv[i+1]));
00088     if ( parameters[i] <= 0.0f )
00089     {
00090       fprintf(stderr, "ERROR: the %i-th parameter has to be positive and not %f\n", i+1, parameters[i]);
00091       return (-1);
00092     }
00093   }
00094 
00095   printf ("The following parameter values will be used:\n");
00096   for ( int i = 0 ; i < num_params ; ++i )
00097     cout << "  " << parameter_names[i] << " = " << parameters[i] << endl;
00098   cout << endl;
00099 
00100   run (parameters[0], parameters[1], parameters[2]);
00101 
00102   return (0);
00103 }
00104 
00105 
00106 
00107 void run (float pair_width, float voxel_size, float max_coplanarity_angle)
00108 {
00109   PointCloud<PointXYZ>::Ptr model_points (new PointCloud<PointXYZ> ());
00110   PointCloud<Normal>::Ptr model_normals (new PointCloud<Normal> ());
00111 
00112   char model_name[] = "../../test/tum_amicelli_box.vtk";
00113 
00114   
00115   if ( !vtk_to_pointcloud (model_name, *model_points, *model_normals) )
00116     return;
00117 
00118   
00119   ObjRecRANSAC objrec (pair_width, voxel_size);
00120   objrec.setMaxCoplanarityAngleDegrees (max_coplanarity_angle);
00121   
00122   objrec.addModel (*model_points, *model_normals, "amicelli");
00123 
00124   const ModelLibrary::Model* model = objrec.getModel ("amicelli");
00125   if ( !model )
00126     return;
00127 
00128   
00129   PCLVisualizer viz;
00130 
00131   
00132   showModelOpps (viz, objrec.getHashTable (), model, pair_width);
00133 
00134   
00135   pcl::PointXYZ sphere_center;
00136   sphere_center.x = model->getOctree ().getFullLeaves ()[0]->getData ()->getPoint ()[0];
00137   sphere_center.y = model->getOctree ().getFullLeaves ()[0]->getData ()->getPoint ()[1];
00138   sphere_center.z = model->getOctree ().getFullLeaves ()[0]->getData ()->getPoint ()[2];
00139   viz.addSphere (sphere_center, pair_width, 0.0, 0.2, 1.0);
00140 
00141 #ifdef _SHOW_MODEL_OCTREE_POINTS_
00142   PointCloud<PointXYZ>::Ptr octree_points (new PointCloud<PointXYZ> ());
00143 
00144   model->getOctree ().getFullLeavesPoints (*octree_points);
00145   viz.addPointCloud (octree_points, "octree points");
00146   viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 5, "octree points");
00147   viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, "octree points");
00148 #endif
00149 
00150 #if defined _SHOW_MODEL_OCTREE_NORMALS_ && defined _SHOW_MODEL_OCTREE_POINTS_
00151   PointCloud<Normal>::Ptr octree_normals (new PointCloud<Normal> ());
00152 
00153   model->getOctree ().getNormalsOfFullLeaves (*octree_normals);
00154   viz.addPointCloudNormals<PointXYZ,Normal> (octree_points, octree_normals, 1, 6.0f, "octree normals");
00155 #endif
00156 
00157   
00158   while (!viz.wasStopped ())
00159   {
00160     
00161     viz.spinOnce (100);
00162     boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00163   }
00164 }
00165 
00166 
00167 
00168 void showModelOpps (PCLVisualizer& viz, const ModelLibrary::HashTable& hash_table, const ModelLibrary::Model* model, float pair_width)
00169 {
00170   printf ("Visualizing ... "); fflush (stdout);
00171 
00172   const ModelLibrary::HashTableCell* cells = hash_table.getVoxels ();
00173   int i, num_cells = hash_table.getNumberOfVoxels ();
00174 
00175   
00176   vtkSmartPointer<vtkPolyData> vtk_opps = vtkSmartPointer<vtkPolyData>::New ();
00177   vtkSmartPointer<vtkPoints> vtk_opps_points = vtkSmartPointer<vtkPoints>::New ();
00178   vtkSmartPointer<vtkCellArray> vtk_opps_lines = vtkSmartPointer<vtkCellArray>::New ();
00179 #ifndef _SHOW_MODEL_OCTREE_NORMALS_
00180   vtkSmartPointer<vtkHedgeHog> vtk_hedge_hog = vtkSmartPointer<vtkHedgeHog>::New ();
00181   vtkSmartPointer<vtkDoubleArray> vtk_normals = vtkSmartPointer<vtkDoubleArray>::New ();
00182   vtk_normals->SetNumberOfComponents (3);
00183 #endif
00184   vtkIdType ids[2] = {0, 1};
00185 
00186   
00187   for ( i = 0 ; i < num_cells ; ++i )
00188   {
00189     
00190         ModelLibrary::HashTableCell::const_iterator res = cells[i].find (model);
00191     if ( res == cells[i].end () )
00192       continue;
00193 
00194     
00195     const ModelLibrary::node_data_pair_list& data_pairs = res->second;
00196 
00197     for ( ModelLibrary::node_data_pair_list::const_iterator dp = data_pairs.begin () ; dp != data_pairs.end () ; ++dp )
00198     {
00199       vtk_opps_points->InsertNextPoint (dp->first->getPoint ());
00200       vtk_opps_points->InsertNextPoint (dp->second->getPoint ());
00201       vtk_opps_lines->InsertNextCell (2, ids);
00202       ids[0] += 2;
00203       ids[1] += 2;
00204 #ifndef _SHOW_MODEL_OCTREE_NORMALS_
00205       vtk_normals->InsertNextTuple3 (dp->first->getNormal  ()[0], dp->first->getNormal  ()[1], dp->first->getNormal  ()[2]);
00206       vtk_normals->InsertNextTuple3 (dp->second->getNormal ()[0], dp->second->getNormal ()[1], dp->second->getNormal ()[2]);
00207 #endif
00208     }
00209   }
00210 
00211   
00212   vtk_opps->SetPoints (vtk_opps_points);
00213   vtk_opps->SetLines (vtk_opps_lines);
00214 #ifndef _SHOW_MODEL_OCTREE_NORMALS_
00215   
00216   vtk_opps->GetPointData ()->SetNormals (vtk_normals);
00217   
00218   vtk_hedge_hog->SetInput (vtk_opps);
00219   vtk_hedge_hog->SetVectorModeToUseNormal ();
00220   vtk_hedge_hog->SetScaleFactor (0.5f*pair_width);
00221   vtk_hedge_hog->Update ();
00222   
00223   viz.addModelFromPolyData (vtk_hedge_hog->GetOutput (), "opps' normals");
00224 #endif
00225 
00226   viz.addModelFromPolyData (vtk_opps, "opps");
00227   viz.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 1.0, 0.0, "opps");
00228 
00229   printf ("done.\n");
00230 }
00231 
00232 
00233 
00234 bool vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>& pcl_normals)
00235 {
00236   size_t len = strlen (file_name);
00237   if ( file_name[len-3] != 'v' || file_name[len-2] != 't' || file_name[len-1] != 'k' )
00238   {
00239     fprintf (stderr, "ERROR: we need a .vtk object!\n");
00240     return false;
00241   }
00242 
00243   
00244   vtkSmartPointer<vtkPolyDataReader> reader = vtkSmartPointer<vtkPolyDataReader>::New ();
00245   reader->SetFileName (file_name);
00246   reader->Update ();
00247 
00248   
00249   vtkPolyData *vtk_poly = reader->GetOutput ();
00250   vtkPoints *vtk_points = vtk_poly->GetPoints ();
00251   vtkIdType num_points = vtk_points->GetNumberOfPoints ();
00252   double p[3];
00253 
00254   pcl_points.resize (num_points);
00255 
00256   
00257   for ( vtkIdType i = 0 ; i < num_points ; ++i )
00258   {
00259     vtk_points->GetPoint (i, p);
00260     pcl_points[i].x = static_cast<float> (p[0]);
00261     pcl_points[i].y = static_cast<float> (p[1]);
00262     pcl_points[i].z = static_cast<float> (p[2]);
00263   }
00264 
00265   
00266   vtkDataArray *vtk_normals = vtk_poly->GetPointData ()->GetNormals ();
00267   if ( !vtk_normals )
00268     return false;
00269 
00270   pcl_normals.resize (num_points);
00271   
00272   for ( vtkIdType i = 0 ; i < num_points ; ++i )
00273   {
00274     vtk_normals->GetTuple (i, p);
00275     pcl_normals[i].normal_x = static_cast<float> (p[0]);
00276     pcl_normals[i].normal_y = static_cast<float> (p[1]);
00277     pcl_normals[i].normal_z = static_cast<float> (p[2]);
00278   }
00279 
00280   return true;
00281 }
00282 
00283