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
00046
00047
00048
00049
00050
00051
00052 #include <pcl/point_cloud.h>
00053 #include <pcl/point_types.h>
00054 #include <pcl/io/pcd_io.h>
00055 #include <pcl/recognition/ransac_based/orr_octree.h>
00056 #include <pcl/visualization/pcl_visualizer.h>
00057 #include <vtkPolyData.h>
00058 #include <vtkAppendPolyData.h>
00059 #include <vtkPolyDataReader.h>
00060 #include <vtkCubeSource.h>
00061 #include <vtkPointData.h>
00062 #include <vtkRenderWindow.h>
00063 #include <vector>
00064 #include <list>
00065 #include <cstdlib>
00066 #include <cstring>
00067 #include <cstdio>
00068
00069 using namespace pcl;
00070 using namespace pcl::visualization;
00071 using namespace pcl::recognition;
00072 using namespace pcl::io;
00073
00074 void run (const char *file_name, float voxel_size);
00075 bool vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>* pcl_normals);
00076 void show_octree (ORROctree* octree, PCLVisualizer& viz, bool show_full_leaves_only);
00077 void node_to_cube (ORROctree::Node* node, vtkAppendPolyData* additive_octree);
00078 void updateViewer (ORROctree& octree, PCLVisualizer& viz, std::vector<ORROctree::Node*>::iterator leaf);
00079
00080 #define _SHOW_OCTREE_NORMALS_
00081
00082 class CallbackParameters
00083 {
00084 public:
00085 CallbackParameters (ORROctree& octree, PCLVisualizer& viz, std::vector<ORROctree::Node*>::iterator leaf)
00086 : octree_(octree),
00087 viz_(viz),
00088 leaf_(leaf)
00089 { }
00090
00091 ORROctree& octree_;
00092 PCLVisualizer& viz_;
00093 std::vector<ORROctree::Node*>::iterator leaf_;
00094 };
00095
00096 int main (int argc, char ** argv)
00097 {
00098 if ( argc != 3 )
00099 {
00100 fprintf(stderr, "\nERROR: Syntax is ./pcl_obj_rec_ransac_orr_octree <vtk file> <leaf_size>\n"
00101 "EXAMPLE: ./pcl_obj_rec_ransac_orr_octree ../../test/tum_rabbit.vtk 6\n\n");
00102 return -1;
00103 }
00104
00105
00106 float voxel_size = static_cast<float> (atof (argv[2]));
00107 if ( voxel_size <= 0.0 )
00108 {
00109 fprintf(stderr, "ERROR: leaf_size has to be positive and not %lf\n", voxel_size);
00110 return -1;
00111 }
00112
00113 run(argv[1], voxel_size);
00114 }
00115
00116
00117
00118 void keyboardCB (const pcl::visualization::KeyboardEvent &event, void* params_void)
00119 {
00120 CallbackParameters* params = static_cast<CallbackParameters*> (params_void);
00121
00122 if (event.getKeySym () == "Left" && event.keyUp ())
00123 {
00124 if (params->leaf_ == params->octree_.getFullLeaves ().begin ())
00125 params->leaf_ = params->octree_.getFullLeaves ().end ();
00126
00127 updateViewer(params->octree_, params->viz_, --params->leaf_);
00128 }
00129 else if (event.getKeySym () == "Right" && event.keyUp ())
00130 {
00131 ++params->leaf_;
00132 if (params->leaf_ == params->octree_.getFullLeaves ().end ())
00133 params->leaf_ = params->octree_.getFullLeaves ().begin ();
00134
00135 updateViewer (params->octree_, params->viz_, params->leaf_);
00136 }
00137 }
00138
00139
00140
00141 void updateViewer (ORROctree& octree, PCLVisualizer& viz, std::vector<ORROctree::Node*>::iterator leaf)
00142 {
00143 viz.removeAllShapes();
00144
00145 const float *b = (*leaf)->getBounds (), *center = (*leaf)->getData ()->getPoint ();
00146 float radius = 0.1f*octree.getRoot ()->getRadius ();
00147
00148
00149 viz.addCube (b[0], b[1], b[2], b[3], b[4], b[5], 0.0, 0.0, 1.0, "main cube");
00150
00151
00152 std::list<ORROctree::Node*> intersected_leaves;
00153 octree.getFullLeavesIntersectedBySphere(center, radius, intersected_leaves);
00154
00155 char cube_id[128];
00156 int i = 0;
00157
00158
00159 for ( std::list<ORROctree::Node*>::iterator it = intersected_leaves.begin () ; it != intersected_leaves.end () ; ++it )
00160 {
00161 sprintf(cube_id, "cube %i", ++i);
00162 b = (*it)->getBounds ();
00163 viz.addCube (b[0], b[1], b[2], b[3], b[4], b[5], 1.0, 1.0, 0.0, cube_id);
00164 }
00165
00166
00167 ORROctree::Node *rand_leaf = octree.getRandomFullLeafOnSphere (center, radius);
00168 if ( rand_leaf )
00169 {
00170 pcl::ModelCoefficients sphere_coeffs;
00171 sphere_coeffs.values.resize (4);
00172 sphere_coeffs.values[0] = rand_leaf->getCenter ()[0];
00173 sphere_coeffs.values[1] = rand_leaf->getCenter ()[1];
00174 sphere_coeffs.values[2] = rand_leaf->getCenter ()[2];
00175 sphere_coeffs.values[3] = 0.5f*(b[1] - b[0]);
00176 viz.addSphere (sphere_coeffs, "random_full_leaf");
00177 }
00178 }
00179
00180
00181
00182 void run (const char* file_name, float voxel_size)
00183 {
00184 PointCloud<PointXYZ>::Ptr points_in (new PointCloud<PointXYZ> ());
00185 PointCloud<PointXYZ>::Ptr points_out (new PointCloud<PointXYZ> ());
00186 PointCloud<Normal>::Ptr normals_in (new PointCloud<Normal> ());
00187 PointCloud<Normal>::Ptr normals_out (new PointCloud<Normal> ());
00188
00189
00190 #ifdef _SHOW_OCTREE_NORMALS_
00191 if ( !vtk_to_pointcloud (file_name, *points_in, &(*normals_in)) )
00192 return;
00193 #else
00194 if ( !vtk_to_pointcloud (file_name, *points_in, NULL) )
00195 return;
00196 #endif
00197
00198
00199 ORROctree octree;
00200 if ( normals_in->size () )
00201 octree.build (*points_in, voxel_size, &*normals_in);
00202 else
00203 octree.build (*points_in, voxel_size);
00204
00205
00206 std::vector<ORROctree::Node*>::iterator leaf = octree.getFullLeaves ().begin ();
00207
00208
00209 octree.getFullLeavesPoints (*points_out);
00210
00211 if ( normals_in->size () )
00212 octree.getNormalsOfFullLeaves (*normals_out);
00213
00214
00215 PCLVisualizer viz;
00216
00217
00218 CallbackParameters params(octree, viz, leaf);
00219 viz.registerKeyboardCallback (keyboardCB, static_cast<void*> (¶ms));
00220
00221
00222 viz.addPointCloud (points_in, "cloud in");
00223 viz.addPointCloud (points_out, "cloud out");
00224 if ( normals_in->size () )
00225 viz.addPointCloudNormals<PointXYZ,Normal> (points_out, normals_out, 1, 6.0f, "normals out");
00226
00227
00228 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "cloud in");
00229 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 5, "cloud out");
00230 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, "cloud out");
00231
00232
00233
00234
00235 updateViewer (octree, viz, leaf);
00236
00237
00238 while (!viz.wasStopped ())
00239 {
00240
00241 viz.spinOnce (100);
00242 boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00243 }
00244 }
00245
00246
00247
00248 bool vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>* pcl_normals)
00249 {
00250 size_t len = strlen (file_name);
00251 if ( file_name[len-3] != 'v' || file_name[len-2] != 't' || file_name[len-1] != 'k' )
00252 {
00253 fprintf (stderr, "ERROR: we need a .vtk object!\n");
00254 return false;
00255 }
00256
00257
00258 vtkSmartPointer<vtkPolyDataReader> reader = vtkSmartPointer<vtkPolyDataReader>::New ();
00259 reader->SetFileName (file_name);
00260 reader->Update ();
00261
00262
00263 vtkPolyData *vtk_poly = reader->GetOutput ();
00264 vtkPoints *vtk_points = vtk_poly->GetPoints ();
00265 vtkIdType num_points = vtk_points->GetNumberOfPoints ();
00266 double p[3];
00267
00268 pcl_points.resize (num_points);
00269
00270
00271 for ( vtkIdType i = 0 ; i < num_points ; ++i )
00272 {
00273 vtk_points->GetPoint (i, p);
00274 pcl_points[i].x = static_cast<float> (p[0]);
00275 pcl_points[i].y = static_cast<float> (p[1]);
00276 pcl_points[i].z = static_cast<float> (p[2]);
00277 }
00278
00279
00280 vtkDataArray *vtk_normals = vtk_poly->GetPointData ()->GetNormals ();
00281 if ( vtk_normals && pcl_normals )
00282 {
00283 pcl_normals->resize (num_points);
00284
00285 for ( vtkIdType i = 0 ; i < num_points ; ++i )
00286 {
00287 vtk_normals->GetTuple (i, p);
00288 (*pcl_normals)[i].normal_x = static_cast<float> (p[0]);
00289 (*pcl_normals)[i].normal_y = static_cast<float> (p[1]);
00290 (*pcl_normals)[i].normal_z = static_cast<float> (p[2]);
00291 }
00292 }
00293
00294 return true;
00295 }
00296
00297
00298
00299 void node_to_cube (ORROctree::Node* node, vtkAppendPolyData* additive_octree)
00300 {
00301
00302 const float *b = node->getBounds ();
00303 vtkSmartPointer<vtkCubeSource> cube = vtkSmartPointer<vtkCubeSource>::New ();
00304 cube->SetBounds (b[0], b[1], b[2], b[3], b[4], b[5]);
00305 cube->Update ();
00306
00307 additive_octree->AddInput (cube->GetOutput ());
00308 }
00309
00310
00311
00312 void show_octree (ORROctree* octree, PCLVisualizer& viz, bool show_full_leaves_only)
00313 {
00314 vtkSmartPointer<vtkPolyData> vtk_octree = vtkSmartPointer<vtkPolyData>::New ();
00315 vtkSmartPointer<vtkAppendPolyData> append = vtkSmartPointer<vtkAppendPolyData>::New ();
00316
00317 cout << "There are " << octree->getFullLeaves ().size () << " full leaves.\n";
00318
00319 if ( show_full_leaves_only )
00320 {
00321 std::vector<ORROctree::Node*>& full_leaves = octree->getFullLeaves ();
00322 for ( std::vector<ORROctree::Node*>::iterator it = full_leaves.begin () ; it != full_leaves.end () ; ++it )
00323
00324 node_to_cube (*it, append);
00325 }
00326 else
00327 {
00328 ORROctree::Node* node;
00329
00330 std::list<ORROctree::Node*> nodes;
00331 nodes.push_back (octree->getRoot ());
00332
00333 while ( !nodes.empty () )
00334 {
00335 node = nodes.front ();
00336 nodes.pop_front ();
00337
00338
00339 if ( node->getChildren () )
00340 {
00341
00342 node_to_cube (node, append);
00343
00344 for ( int i = 0 ; i < 8 ; ++i )
00345 nodes.push_back (node->getChild (i));
00346 }
00347
00348 else if ( node->getData () )
00349 node_to_cube (node, append);
00350 }
00351 }
00352
00353
00354 std::vector<ORROctree::Node*>::iterator first_leaf = octree->getFullLeaves ().begin ();
00355 if ( first_leaf != octree->getFullLeaves ().end () )
00356 printf("leaf size = %f\n", (*first_leaf)->getBounds ()[1] - (*first_leaf)->getBounds ()[0]);
00357
00358
00359 append->Update();
00360 vtk_octree->DeepCopy (append->GetOutput ());
00361
00362
00363 vtkRenderer *renderer = viz.getRenderWindow ()->GetRenderers ()->GetFirstRenderer ();
00364 vtkSmartPointer<vtkActor> octree_actor = vtkSmartPointer<vtkActor>::New();
00365 vtkSmartPointer<vtkDataSetMapper> mapper = vtkSmartPointer<vtkDataSetMapper>::New ();
00366 mapper->SetInput(vtk_octree);
00367 octree_actor->SetMapper(mapper);
00368
00369
00370 octree_actor->GetProperty ()->SetColor (1.0, 1.0, 1.0);
00371 octree_actor->GetProperty ()->SetLineWidth (1);
00372 octree_actor->GetProperty ()->SetRepresentationToWireframe ();
00373 renderer->AddActor(octree_actor);
00374 }
00375
00376