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/segmentation/sac_segmentation.h>
00046 #include <pcl/recognition/ransac_based/obj_rec_ransac.h>
00047 #include <pcl/visualization/pcl_visualizer.h>
00048 #include <pcl/console/print.h>
00049 #include <pcl/console/parse.h>
00050 #include <pcl/io/pcd_io.h>
00051 #include <pcl/point_cloud.h>
00052 #include <vtkPolyDataReader.h>
00053 #include <vtkDoubleArray.h>
00054 #include <vtkDataArray.h>
00055 #include <vtkPointData.h>
00056 #include <vtkHedgeHog.h>
00057 #include <vtkTransformPolyDataFilter.h>
00058 #include <vtkRenderer.h>
00059 #include <vtkRenderWindow.h>
00060 #include <vtkTransform.h>
00061 #include <cstdio>
00062 #include <vector>
00063 #include <list>
00064
00065 using namespace std;
00066 using namespace pcl;
00067 using namespace io;
00068 using namespace console;
00069 using namespace recognition;
00070 using namespace visualization;
00071
00072 class CallbackParameters;
00073
00074 void keyboardCB (const pcl::visualization::KeyboardEvent &event, void* params_void);
00075 void update (CallbackParameters* params);
00076 bool vtk2PointCloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>& pcl_normals, vtkPolyData* vtk_data);
00077 void run (float pair_width, float voxel_size, float max_coplanarity_angle);
00078 bool loadScene (const char* file_name, PointCloud<PointXYZ>& non_plane_points, PointCloud<Normal>& non_plane_normals,
00079 PointCloud<PointXYZ>& plane_points);
00080
00081
00082 #define _SHOW_OCTREE_POINTS_
00083
00084
00085
00086 class CallbackParameters
00087 {
00088 public:
00089 CallbackParameters (ObjRecRANSAC& objrec, PCLVisualizer& viz, PointCloud<PointXYZ>& scene_points, PointCloud<Normal>& scene_normals)
00090 : objrec_ (objrec),
00091 viz_ (viz),
00092 scene_points_ (scene_points),
00093 scene_normals_ (scene_normals)
00094 {}
00095
00096 ObjRecRANSAC& objrec_;
00097 PCLVisualizer& viz_;
00098 PointCloud<PointXYZ>& scene_points_;
00099 PointCloud<Normal>& scene_normals_;
00100 list<vtkActor*> actors_;
00101 };
00102
00103
00104
00105 int
00106 main (int argc, char** argv)
00107 {
00108 printf ("\nUsage: ./pcl_obj_rec_ransac_scene_opps <pair_width> <voxel_size> <max_coplanarity_angle>\n\n");
00109
00110 const int num_params = 3;
00111 float parameters[num_params] = {40.0f, 5.0f, 15.0f};
00112 string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"};
00113
00114
00115 for ( int i = 0 ; i < argc-1 && i < num_params ; ++i )
00116 {
00117 parameters[i] = static_cast<float> (atof (argv[i+1]));
00118 if ( parameters[i] <= 0.0f )
00119 {
00120 fprintf(stderr, "ERROR: the %i-th parameter has to be positive and not %f\n", i+1, parameters[i]);
00121 return (-1);
00122 }
00123 }
00124
00125 printf ("The following parameter values will be used:\n");
00126 for ( int i = 0 ; i < num_params ; ++i )
00127 cout << " " << parameter_names[i] << " = " << parameters[i] << endl;
00128 cout << endl;
00129
00130 run (parameters[0], parameters[1], parameters[2]);
00131 }
00132
00133
00134
00135 void
00136 run (float pair_width, float voxel_size, float max_coplanarity_angle)
00137 {
00138
00139 ObjRecRANSAC objrec (pair_width, voxel_size);
00140 objrec.setMaxCoplanarityAngleDegrees (max_coplanarity_angle);
00141
00142
00143 list<string> model_names;
00144 model_names.push_back (string ("tum_amicelli_box"));
00145 model_names.push_back (string ("tum_rusk_box"));
00146 model_names.push_back (string ("tum_soda_bottle"));
00147
00148 list<PointCloud<PointXYZ>::Ptr> model_points_list;
00149 list<PointCloud<Normal>::Ptr> model_normals_list;
00150 list<vtkSmartPointer<vtkPolyData> > vtk_models_list;
00151
00152
00153 for ( list<string>::iterator it = model_names.begin () ; it != model_names.end () ; ++it )
00154 {
00155 PointCloud<PointXYZ>::Ptr model_points (new PointCloud<PointXYZ> ());
00156 model_points_list.push_back (model_points);
00157
00158 PointCloud<Normal>::Ptr model_normals (new PointCloud<Normal> ());
00159 model_normals_list.push_back (model_normals);
00160
00161 vtkSmartPointer<vtkPolyData> vtk_model = vtkSmartPointer<vtkPolyData>::New ();
00162 vtk_models_list.push_back (vtk_model);
00163
00164
00165 string file_name = string("../../test/") + *it + string (".vtk");
00166
00167
00168 if ( !vtk2PointCloud (file_name.c_str (), *model_points, *model_normals, vtk_model) )
00169 continue;
00170
00171
00172 objrec.addModel (*model_points, *model_normals, *it, vtk_model);
00173 }
00174
00175
00176 PointCloud<PointXYZ>::Ptr non_plane_points (new PointCloud<PointXYZ> ()), plane_points (new PointCloud<PointXYZ> ());
00177 PointCloud<Normal>::Ptr non_plane_normals (new PointCloud<Normal> ());
00178
00179
00180 if ( !loadScene ("../../test/tum_table_scene.vtk", *non_plane_points, *non_plane_normals, *plane_points) )
00181 return;
00182
00183
00184 PCLVisualizer viz;
00185 CallbackParameters params(objrec, viz, *non_plane_points, *non_plane_normals);
00186 viz.registerKeyboardCallback (keyboardCB, static_cast<void*> (¶ms));
00187
00188
00189 update (¶ms);
00190
00191
00192 #ifdef _SHOW_OCTREE_
00193 show_octree(objrec.getSceneOctree (), viz);
00194 #endif
00195
00196 #ifdef _SHOW_SCENE_POINTS_
00197 viz.addPointCloud (scene_points, "scene points");
00198 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "scene points");
00199 #endif
00200
00201 #ifdef _SHOW_OCTREE_POINTS_
00202 PointCloud<PointXYZ>::Ptr octree_points (new PointCloud<PointXYZ> ());
00203 objrec.getSceneOctree ().getFullLeavesPoints (*octree_points);
00204 viz.addPointCloud (octree_points, "octree points");
00205
00206 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, "octree points");
00207
00208 viz.addPointCloud (plane_points, "plane points");
00209 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 0.9, 0.9, 0.9, "plane points");
00210 #endif
00211
00212 #if defined _SHOW_OCTREE_NORMALS_ && defined _SHOW_OCTREE_POINTS_
00213 PointCloud<Normal>::Ptr normals_octree (new PointCloud<Normal> ());
00214 objrec.getSceneOctree ().getNormalsOfFullLeaves (*normals_octree);
00215 viz.addPointCloudNormals<PointXYZ,Normal> (points_octree, normals_octree, 1, 6.0f, "normals out");
00216 #endif
00217
00218
00219 while (!viz.wasStopped ())
00220 {
00221
00222 viz.spinOnce (100);
00223 boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00224 }
00225 }
00226
00227
00228
00229 void
00230 keyboardCB (const pcl::visualization::KeyboardEvent &event, void* params_void)
00231 {
00232 if (event.getKeyCode () == 13 && event.keyUp ())
00233 update (static_cast<CallbackParameters*> (params_void));
00234 }
00235
00236
00237
00238 void
00239 update (CallbackParameters* params)
00240 {
00241
00242 vtkRenderer *renderer = params->viz_.getRenderWindow ()->GetRenderers ()->GetFirstRenderer ();
00243 for ( list<vtkActor*>::iterator it = params->actors_.begin () ; it != params->actors_.end () ; ++it )
00244 renderer->RemoveActor (*it);
00245 params->actors_.clear ();
00246
00247
00248 list<ObjRecRANSAC::Output> rec_output;
00249
00250
00251 ObjRecRANSAC& objrec = params->objrec_;
00252
00253
00254 objrec.recognize (params->scene_points_, params->scene_normals_, rec_output);
00255 int i = 0;
00256
00257
00258 for ( list<ObjRecRANSAC::Output>::iterator it = rec_output.begin () ; it != rec_output.end () ; ++it, ++i )
00259 {
00260 cout << it->object_name_ << " has a confidence value of " << it->match_confidence_ << endl;
00261
00262
00263 vtkSmartPointer<vtkPolyData> vtk_model = vtkSmartPointer<vtkPolyData>::New ();
00264 vtk_model->DeepCopy (static_cast<vtkPolyData*> (it->user_data_));
00265
00266
00267 vtkSmartPointer<vtkMatrix4x4> vtk_mat = vtkSmartPointer<vtkMatrix4x4>::New ();
00268 vtk_mat->Identity ();
00269 const float *t = it->rigid_transform_;
00270
00271 vtk_mat->SetElement (0, 0, t[0]); vtk_mat->SetElement (0, 1, t[1]); vtk_mat->SetElement (0, 2, t[2]);
00272 vtk_mat->SetElement (1, 0, t[3]); vtk_mat->SetElement (1, 1, t[4]); vtk_mat->SetElement (1, 2, t[5]);
00273 vtk_mat->SetElement (2, 0, t[6]); vtk_mat->SetElement (2, 1, t[7]); vtk_mat->SetElement (2, 2, t[8]);
00274
00275 vtk_mat->SetElement (0, 3, t[9]); vtk_mat->SetElement (1, 3, t[10]); vtk_mat->SetElement (2, 3, t[11]);
00276
00277
00278 vtkSmartPointer<vtkTransform> vtk_transform = vtkSmartPointer<vtkTransform>::New ();
00279 vtk_transform->SetMatrix (vtk_mat);
00280
00281
00282 vtkSmartPointer<vtkTransformPolyDataFilter> vtk_transformator = vtkSmartPointer<vtkTransformPolyDataFilter>::New ();
00283 vtk_transformator->SetTransform (vtk_transform);
00284 vtk_transformator->SetInput (vtk_model);
00285 vtk_transformator->Update ();
00286
00287
00288 vtkSmartPointer<vtkActor> vtk_actor = vtkSmartPointer<vtkActor>::New();
00289 vtkSmartPointer<vtkPolyDataMapper> vtk_mapper = vtkSmartPointer<vtkPolyDataMapper>::New ();
00290 vtk_mapper->SetInput(vtk_transformator->GetOutput ());
00291 vtk_actor->SetMapper(vtk_mapper);
00292
00293 vtk_actor->GetProperty ()->SetColor (0.6, 0.7, 0.9);
00294 renderer->AddActor(vtk_actor);
00295 params->actors_.push_back (vtk_actor);
00296
00297 #ifdef _SHOW_TRANSFORM_SPACE_
00298 if ( transform_space.getPositionCellBounds ((*acc_hypo)->pos_id_, cb) )
00299 {
00300 sprintf (pos_cell_name, "cell [%i, %i, %i]\n", (*acc_hypo)->pos_id_[0], (*acc_hypo)->pos_id_[1], (*acc_hypo)->pos_id_[2]);
00301 params->viz_.addCube (cb[0], cb[1], cb[2], cb[3], cb[4], cb[5], 1.0, 1.0, 1.0, pos_cell_name);
00302 }
00303 else
00304 printf ("WARNING: no cell at position [%i, %i, %i]\n", (*acc_hypo)->pos_id_[0], (*acc_hypo)->pos_id_[1], (*acc_hypo)->pos_id_[2]);
00305 #endif
00306 }
00307 }
00308
00309
00310
00311 bool
00312 loadScene (const char* file_name, PointCloud<PointXYZ>& non_plane_points, PointCloud<Normal>& non_plane_normals,
00313 PointCloud<PointXYZ>& plane_points)
00314 {
00315 PointCloud<PointXYZ>::Ptr all_points (new PointCloud<PointXYZ> ());
00316 PointCloud<Normal>::Ptr all_normals (new PointCloud<Normal> ());
00317
00318
00319 if ( !vtk2PointCloud (file_name, *all_points, *all_normals, NULL) )
00320 return false;
00321
00322
00323 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
00324 pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
00325
00326 pcl::SACSegmentation<pcl::PointXYZ> seg;
00327
00328 seg.setOptimizeCoefficients (true);
00329
00330 seg.setModelType (pcl::SACMODEL_PLANE);
00331 seg.setMethodType (pcl::SAC_RANSAC);
00332 seg.setDistanceThreshold (10.0);
00333
00334 seg.setInputCloud (all_points);
00335 seg.segment (*inliers, *coefficients);
00336
00337 if (inliers->indices.size () == 0)
00338 {
00339 PCL_ERROR ("Could not estimate a planar model for the given dataset.");
00340 return false;
00341 }
00342
00343
00344 non_plane_points.resize (all_points->size () - inliers->indices.size ());
00345 non_plane_normals.resize (all_points->size () - inliers->indices.size ());
00346 plane_points.resize (inliers->indices.size ());
00347
00348
00349 sort (inliers->indices.begin (), inliers->indices.end ());
00350 size_t i, j, id;
00351
00352 for ( i = 0, j = 0, id = 0 ; i < inliers->indices.size () ; )
00353 {
00354 if ( id == inliers->indices[i] )
00355 {
00356 plane_points.points[i] = all_points->points[id];
00357 ++id;
00358 ++i;
00359 }
00360 else
00361 {
00362 non_plane_points.points[j] = all_points->points[id];
00363 non_plane_normals.points[j] = all_normals->points[id];
00364 ++id;
00365 ++j;
00366 }
00367 }
00368
00369
00370 for ( ; id < all_points->size () ; ++id, ++j )
00371 {
00372 non_plane_points.points[j] = all_points->points[id];
00373 non_plane_normals.points[j] = all_normals->points[id];
00374 }
00375
00376 return true;
00377 }
00378
00379
00380
00381 bool
00382 vtk2PointCloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>& pcl_normals, vtkPolyData* vtk_data)
00383 {
00384 size_t len = strlen (file_name);
00385 if ( file_name[len-3] != 'v' || file_name[len-2] != 't' || file_name[len-1] != 'k' )
00386 {
00387 fprintf (stderr, "ERROR: we need a .vtk object!\n");
00388 return false;
00389 }
00390
00391
00392 vtkSmartPointer<vtkPolyDataReader> reader = vtkSmartPointer<vtkPolyDataReader>::New ();
00393 reader->SetFileName (file_name);
00394 reader->Update ();
00395
00396
00397 vtkPolyData *vtk_poly = reader->GetOutput ();
00398 vtkPoints *vtk_points = vtk_poly->GetPoints ();
00399 vtkIdType num_points = vtk_points->GetNumberOfPoints ();
00400 double p[3];
00401
00402
00403 if ( vtk_data )
00404 vtk_data->DeepCopy (vtk_poly);
00405
00406 pcl_points.resize (num_points);
00407
00408
00409 for ( vtkIdType i = 0 ; i < num_points ; ++i )
00410 {
00411 vtk_points->GetPoint (i, p);
00412 pcl_points[i].x = static_cast<float> (p[0]);
00413 pcl_points[i].y = static_cast<float> (p[1]);
00414 pcl_points[i].z = static_cast<float> (p[2]);
00415 }
00416
00417
00418 vtkDataArray *vtk_normals = vtk_poly->GetPointData ()->GetNormals ();
00419 if ( !vtk_normals )
00420 return false;
00421
00422 pcl_normals.resize (num_points);
00423
00424 for ( vtkIdType i = 0 ; i < num_points ; ++i )
00425 {
00426 vtk_normals->GetTuple (i, p);
00427 pcl_normals[i].normal_x = static_cast<float> (p[0]);
00428 pcl_normals[i].normal_y = static_cast<float> (p[1]);
00429 pcl_normals[i].normal_z = static_cast<float> (p[2]);
00430 }
00431
00432 return true;
00433 }
00434
00435