obj_rec_ransac_hash_table.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
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 copyright holder(s) 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 
00036 /*
00037  * obj_rec_ransac_hash_table.cpp
00038  *
00039  *  Created on: Jun 20, 2012
00040  *      Author: papazov
00041  *
00042  *  Visualizes the hash table cell entries belonging to a model. Since the hash table is a 3D cube structure, each cell
00043  *  is a cube in 3D. It is visualized by a cube which is scaled according to the number of entries in the cell -> the more
00044  *  entries the bigger the cube.
00045  */
00046 
00047 #include <pcl/recognition/ransac_based/obj_rec_ransac.h>
00048 #include <pcl/visualization/pcl_visualizer.h>
00049 #include <pcl/console/print.h>
00050 #include <pcl/console/parse.h>
00051 #include <pcl/io/pcd_io.h>
00052 #include <pcl/point_cloud.h>
00053 #include <vtkPolyDataReader.h>
00054 #include <vtkDoubleArray.h>
00055 #include <vtkDataArray.h>
00056 #include <vtkPointData.h>
00057 #include <vtkGlyph3D.h>
00058 #include <cstdio>
00059 #include <vector>
00060 
00061 using namespace std;
00062 using namespace pcl;
00063 using namespace io;
00064 using namespace console;
00065 using namespace recognition;
00066 using namespace visualization;
00067 
00068 inline double
00069 my_sqr (double a){ return a*a;}
00070 
00071 bool vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& points_in, PointCloud<Normal>& normals_in, double bounds[6]);
00072 void visualize (const ModelLibrary::HashTable& hash_table);
00073 
00074 //===========================================================================================================================================
00075 
00076 int
00077 main (int argc, char** argv)
00078 {
00079   // Make sure that we have the right number of arguments
00080   if (argc != 2)
00081   {
00082     print_info ("\nVisualizes the hash table after adding the provided mesh to it.\n"
00083         "usage:\n"
00084         "./obj_rec_ransac_hash_table <mesh.vtk>\n");
00085     return (-1);
00086   }
00087 
00088   ObjRecRANSAC::PointCloudIn points_in;
00089   ObjRecRANSAC::PointCloudN normals_in;
00090   double b[6];
00091 
00092   if ( !vtk_to_pointcloud (argv[1], points_in, normals_in, b) )
00093     return (-1);
00094 
00095   // Compute the bounding box diagonal
00096   float diag = static_cast<float> (sqrt (my_sqr (b[1]-b[0]) + my_sqr (b[3]-b[2]) + my_sqr (b[5]-b[4])));
00097 
00098   // Create the recognition object (we need it only for its hash table)
00099   ObjRecRANSAC objrec (diag/8.0f, diag/60.0f);
00100   objrec.addModel (points_in, normals_in, "test_model");
00101 
00102   // Start visualization (and the main VTK loop)
00103   visualize (objrec.getHashTable ());
00104 
00105   return (0);
00106 }
00107 
00108 //===========================================================================================================================================
00109 
00110 bool vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& points_in, PointCloud<Normal>& normals_in, double b[6])
00111 {
00112   size_t len = strlen (file_name);
00113   if ( file_name[len-3] != 'v' || file_name[len-2] != 't' || file_name[len-1] != 'k' )
00114   {
00115     fprintf (stderr, "ERROR: we need a .vtk object!\n");
00116     return false;
00117   }
00118 
00119   // Load the model
00120   vtkSmartPointer<vtkPolyDataReader> reader = vtkSmartPointer<vtkPolyDataReader>::New ();
00121   reader->SetFileName (file_name);
00122   reader->Update ();
00123 
00124   // Get the points
00125   vtkPolyData *vtk_poly = reader->GetOutput ();
00126   vtkPoints *vtk_points = vtk_poly->GetPoints ();
00127   vtkIdType num_points = vtk_points->GetNumberOfPoints ();
00128   double p[3];
00129 
00130   vtk_poly->ComputeBounds ();
00131   vtk_poly->GetBounds (b);
00132   points_in.resize (num_points);
00133 
00134   // Copy the points
00135   for ( vtkIdType i = 0 ; i < num_points ; ++i )
00136   {
00137     vtk_points->GetPoint (i, p);
00138     points_in[i].x = static_cast<float> (p[0]);
00139     points_in[i].y = static_cast<float> (p[1]);
00140     points_in[i].z = static_cast<float> (p[2]);
00141   }
00142 
00143   // Check if we have normals
00144   vtkDataArray *vtk_normals = vtk_poly->GetPointData ()->GetNormals ();
00145   if ( vtk_normals )
00146   {
00147     normals_in.resize (num_points);
00148     // Copy the normals
00149     for ( vtkIdType i = 0 ; i < num_points ; ++i )
00150     {
00151       vtk_normals->GetTuple (i, p);
00152       normals_in[i].normal_x = static_cast<float> (p[0]);
00153       normals_in[i].normal_y = static_cast<float> (p[1]);
00154       normals_in[i].normal_z = static_cast<float> (p[2]);
00155     }
00156   }
00157 
00158   return true;
00159 }
00160 
00161 //===========================================================================================================================================
00162 
00163 void
00164 visualize (const ModelLibrary::HashTable& hash_table)
00165 {
00166   PCLVisualizer vis;
00167   vis.setBackgroundColor (0.1, 0.1, 0.1);
00168 
00169   const ModelLibrary::HashTableCell* cells = hash_table.getVoxels ();
00170   size_t max_num_entries = 0;
00171   int i, id3[3], num_cells = hash_table.getNumberOfVoxels ();
00172   float half_side, b[6], cell_center[3], spacing = hash_table.getVoxelSpacing ()[0];
00173   char cube_id[128];
00174 
00175   // Just get the maximal number of entries in the cells
00176   for ( i = 0 ; i < num_cells ; ++i, ++cells )
00177   {
00178     if (cells->size ()) // That's the number of models in the cell (it's maximum one, since we loaded only one model)
00179     {
00180       size_t num_entries = (*cells->begin ()).second.size(); // That's the number of entries in the current cell for the model we loaded
00181       // Get the max number of entries
00182       if ( num_entries > max_num_entries )
00183         max_num_entries = num_entries;
00184     }
00185   }
00186 
00187   // Now, that we have the max. number of entries, we can compute the
00188   // right scale factor for the spheres
00189   float s = (0.5f*spacing)/static_cast<float> (max_num_entries);
00190 
00191   cout << "s = " << s << ", max_num_entries = " << max_num_entries << endl;
00192 
00193   // Now, render a sphere with the right radius at the right place
00194   for ( i = 0, cells = hash_table.getVoxels () ; i < num_cells ; ++i, ++cells )
00195   {
00196     // Does the cell have any entries?
00197     if (cells->size ())
00198     {
00199       hash_table.compute3dId (i, id3);
00200       hash_table.computeVoxelCenter (id3, cell_center);
00201 
00202       // That's half of the cube's side length
00203       half_side = s*static_cast<float> ((*cells->begin ()).second.size ());
00204 
00205       // Adjust the bounds of the cube
00206       b[0] = cell_center[0] - half_side; b[1] = cell_center[0] + half_side;
00207       b[2] = cell_center[1] - half_side; b[3] = cell_center[1] + half_side;
00208       b[4] = cell_center[2] - half_side; b[5] = cell_center[2] + half_side;
00209 
00210       // Set the id
00211       sprintf (cube_id, "cube %i", i);
00212 
00213       // Add to the visualizer
00214       vis.addCube (b[0], b[1], b[2], b[3], b[4], b[5], 1.0, 1.0, 0.0, cube_id);
00215     }
00216   }
00217 
00218   vis.addCoordinateSystem(1.5);
00219   vis.resetCamera ();
00220 
00221   // Enter the main loop
00222   while (!vis.wasStopped ())
00223   {
00224     vis.spinOnce (100);
00225     boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00226   }
00227 }
00228 


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