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 #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 <vtkRenderWindow.h>
00054 #include <vtkTransformPolyDataFilter.h>
00055 #include <vtkDoubleArray.h>
00056 #include <vtkDataArray.h>
00057 #include <vtkPointData.h>
00058 #include <vtkTransform.h>
00059 #include <vtkHedgeHog.h>
00060 #include <vtkMatrix4x4.h>
00061 #include <algorithm>
00062 #include <cstdio>
00063 #include <vector>
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 bool
00073 vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>& pcl_normals, vtkPolyData* vtk_dst = NULL);
00074
00075
00076 #define _SHOW_OCTREE_POINTS_
00077
00078
00079
00080 class CallbackParameters
00081 {
00082 public:
00083 CallbackParameters (ObjRecRANSAC& objrec, PCLVisualizer& viz, PointCloud<PointXYZ>& points, PointCloud<Normal>& normals, int num_hypotheses_to_show)
00084 : objrec_ (objrec),
00085 viz_ (viz),
00086 points_ (points),
00087 normals_ (normals),
00088 num_hypotheses_to_show_ (num_hypotheses_to_show),
00089 show_models_ (true)
00090 { }
00091
00092 ObjRecRANSAC& objrec_;
00093 PCLVisualizer& viz_;
00094 PointCloud<PointXYZ>& points_;
00095 PointCloud<Normal>& normals_;
00096 int num_hypotheses_to_show_;
00097 list<vtkActor*> actors_, model_actors_;
00098 bool show_models_;
00099 };
00100
00101
00102
00103 bool
00104 vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>& pcl_normals, vtkPolyData* vtk_dst)
00105 {
00106 size_t len = strlen (file_name);
00107 if ( file_name[len-3] != 'v' || file_name[len-2] != 't' || file_name[len-1] != 'k' )
00108 {
00109 fprintf (stderr, "ERROR: we need a .vtk object!\n");
00110 return false;
00111 }
00112
00113
00114 vtkSmartPointer<vtkPolyDataReader> reader = vtkSmartPointer<vtkPolyDataReader>::New ();
00115 reader->SetFileName (file_name);
00116 reader->Update ();
00117
00118
00119 vtkPolyData *vtk_poly = reader->GetOutput ();
00120 vtkPoints *vtk_points = vtk_poly->GetPoints ();
00121 vtkIdType num_points = vtk_points->GetNumberOfPoints ();
00122 double p[3];
00123
00124 pcl_points.resize (num_points);
00125
00126
00127 if ( vtk_dst )
00128 vtk_dst->DeepCopy (vtk_poly);
00129
00130
00131 for ( vtkIdType i = 0 ; i < num_points ; ++i )
00132 {
00133 vtk_points->GetPoint (i, p);
00134 pcl_points[i].x = static_cast<float> (p[0]);
00135 pcl_points[i].y = static_cast<float> (p[1]);
00136 pcl_points[i].z = static_cast<float> (p[2]);
00137 }
00138
00139
00140 vtkDataArray *vtk_normals = vtk_poly->GetPointData ()->GetNormals ();
00141 if ( !vtk_normals )
00142 return false;
00143
00144 pcl_normals.resize (num_points);
00145
00146 for ( vtkIdType i = 0 ; i < num_points ; ++i )
00147 {
00148 vtk_normals->GetTuple (i, p);
00149 pcl_normals[i].normal_x = static_cast<float> (p[0]);
00150 pcl_normals[i].normal_y = static_cast<float> (p[1]);
00151 pcl_normals[i].normal_z = static_cast<float> (p[2]);
00152 }
00153
00154 return true;
00155 }
00156
00157
00158
00159 void
00160 showHypothesisAsCoordinateFrame (Hypothesis& hypo, CallbackParameters* parameters, string frame_name)
00161 {
00162 float rot_col[3], x_dir[3], y_dir[3], z_dir[3], origin[3], scale = 2.0f*parameters->objrec_.getPairWidth ();
00163 pcl::ModelCoefficients coeffs; coeffs.values.resize (6);
00164
00165
00166 aux::transform (hypo.rigid_transform_, hypo.obj_model_->getOctreeCenterOfMass (), origin);
00167 coeffs.values[0] = origin[0];
00168 coeffs.values[1] = origin[1];
00169 coeffs.values[2] = origin[2];
00170
00171 rot_col[0] = hypo.rigid_transform_[0];
00172 rot_col[1] = hypo.rigid_transform_[3];
00173 rot_col[2] = hypo.rigid_transform_[6];
00174 aux::mult3 (rot_col, scale, x_dir);
00175 rot_col[0] = hypo.rigid_transform_[1];
00176 rot_col[1] = hypo.rigid_transform_[4];
00177 rot_col[2] = hypo.rigid_transform_[7];
00178 aux::mult3 (rot_col, scale, y_dir);
00179 rot_col[0] = hypo.rigid_transform_[2];
00180 rot_col[1] = hypo.rigid_transform_[5];
00181 rot_col[2] = hypo.rigid_transform_[8];
00182 aux::mult3 (rot_col, scale, z_dir);
00183
00184
00185 coeffs.values[3] = x_dir[0];
00186 coeffs.values[4] = x_dir[1];
00187 coeffs.values[5] = x_dir[2];
00188 parameters->viz_.addLine (coeffs, frame_name + "_x_axis");
00189 parameters->viz_.setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, frame_name + "_x_axis");
00190
00191
00192 coeffs.values[3] = y_dir[0];
00193 coeffs.values[4] = y_dir[1];
00194 coeffs.values[5] = y_dir[2];
00195 parameters->viz_.addLine (coeffs, frame_name + "_y_axis");
00196 parameters->viz_.setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 0.0, 1.0, 0.0, frame_name + "_y_axis");
00197
00198
00199 coeffs.values[3] = z_dir[0];
00200 coeffs.values[4] = z_dir[1];
00201 coeffs.values[5] = z_dir[2];
00202 parameters->viz_.addLine (coeffs, frame_name + "_z_axis");
00203 parameters->viz_.setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 0.0, 0.0, 1.0, frame_name + "_z_axis");
00204 }
00205
00206
00207
00208 bool
00209 compareHypotheses (const Hypothesis& a, const Hypothesis& b)
00210 {
00211 return (static_cast<bool> (a.match_confidence_ > b.match_confidence_));
00212 }
00213
00214
00215
00216 void
00217 arrayToVtkMatrix (const float* a, vtkMatrix4x4* m)
00218 {
00219
00220 m->SetElement (0, 0, a[0]); m->SetElement (0, 1, a[1]); m->SetElement (0, 2, a[2]);
00221 m->SetElement (1, 0, a[3]); m->SetElement (1, 1, a[4]); m->SetElement (1, 2, a[5]);
00222 m->SetElement (2, 0, a[6]); m->SetElement (2, 1, a[7]); m->SetElement (2, 2, a[8]);
00223
00224 m->SetElement (0, 3, a[9]); m->SetElement (1, 3, a[10]); m->SetElement (2, 3, a[11]);
00225 }
00226
00227
00228
00229 void
00230 update (CallbackParameters* params)
00231 {
00232 list<ObjRecRANSAC::Output> dummy_output;
00233
00234
00235 params->objrec_.recognize (params->points_, params->normals_, dummy_output);
00236
00237
00238 vtkRenderer *renderer = params->viz_.getRenderWindow ()->GetRenderers ()->GetFirstRenderer ();
00239 for ( list<vtkActor*>::iterator it = params->actors_.begin () ; it != params->actors_.end () ; ++it )
00240 renderer->RemoveActor (*it);
00241 params->actors_.clear ();
00242
00243 for ( list<vtkActor*>::iterator it = params->model_actors_.begin () ; it != params->model_actors_.end () ; ++it )
00244 renderer->RemoveActor (*it);
00245 params->model_actors_.clear ();
00246
00247 params->viz_.removeAllShapes ();
00248
00249 #ifdef _SHOW_SCENE_OPPS_
00250
00251 const list<ObjRecRANSAC::OrientedPointPair>& opps = params->objrec_.getSampledOrientedPointPairs ();
00252
00253 vtkSmartPointer<vtkPolyData> vtk_opps = vtkSmartPointer<vtkPolyData>::New ();
00254 vtkSmartPointer<vtkPoints> vtk_opps_points = vtkSmartPointer<vtkPoints>::New ();
00255 vtk_opps_points->SetNumberOfPoints (2*static_cast<vtkIdType> (opps.size ()));
00256 vtkSmartPointer<vtkCellArray> vtk_opps_lines = vtkSmartPointer<vtkCellArray>::New ();
00257
00258 vtkSmartPointer<vtkDoubleArray> vtk_normals = vtkSmartPointer<vtkDoubleArray>::New ();
00259 vtk_normals->SetNumberOfComponents (3);
00260 vtk_normals->SetNumberOfTuples (2*static_cast<vtkIdType> (opps.size ()));
00261 vtkIdType ids[2] = {0, 1};
00262
00263
00264 for ( list<ObjRecRANSAC::OrientedPointPair>::const_iterator it = opps.begin () ; it != opps.end () ; ++it )
00265 {
00266 vtk_opps_points->SetPoint (ids[0], it->p1_[0], it->p1_[1], it->p1_[2]);
00267 vtk_opps_points->SetPoint (ids[1], it->p2_[0], it->p2_[1], it->p2_[2]);
00268 vtk_opps_lines->InsertNextCell (2, ids);
00269
00270 vtk_normals->SetTuple3 (ids[0], it->n1_[0], it->n1_[1], it->n1_[2]);
00271 vtk_normals->SetTuple3 (ids[1], it->n2_[0], it->n2_[1], it->n2_[2]);
00272
00273 ids[0] += 2;
00274 ids[1] += 2;
00275 }
00276 vtk_opps->SetPoints (vtk_opps_points);
00277 vtk_opps->GetPointData ()->SetNormals (vtk_normals);
00278 vtk_opps->SetLines (vtk_opps_lines);
00279
00280 vtkSmartPointer<vtkHedgeHog> vtk_hh = vtkSmartPointer<vtkHedgeHog>::New ();
00281 vtk_hh->SetVectorModeToUseNormal ();
00282 vtk_hh->SetScaleFactor (0.5f*params->objrec_.getPairWidth ());
00283 vtk_hh->SetInput (vtk_opps);
00284 vtk_hh->Update ();
00285
00286
00287 string lines_str_id = "opps";
00288 params->viz_.addModelFromPolyData (vtk_opps, lines_str_id);
00289 params->viz_.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0.0, 0.0, 1.0, lines_str_id);
00290
00291 string normals_str_id = "opps normals";
00292 params->viz_.addModelFromPolyData (vtk_hh->GetOutput (), normals_str_id);
00293 params->viz_.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 1.0, 0.0, normals_str_id);
00294 #endif
00295
00296
00297 vector<Hypothesis> accepted_hypotheses;
00298 params->objrec_.getAcceptedHypotheses (accepted_hypotheses);
00299 int i = 0;
00300
00301
00302 std::sort(accepted_hypotheses.begin (), accepted_hypotheses.end (), compareHypotheses);
00303
00304
00305 for ( vector<Hypothesis>::iterator acc_hypo = accepted_hypotheses.begin () ; i < params->num_hypotheses_to_show_ && acc_hypo != accepted_hypotheses.end () ; ++i, ++acc_hypo )
00306 {
00307
00308 char frame_name[128];
00309 sprintf (frame_name, "frame_%i", i+1);
00310 showHypothesisAsCoordinateFrame (*acc_hypo, params, frame_name);
00311
00312
00313 vtkSmartPointer<vtkPolyData> vtk_model = vtkSmartPointer<vtkPolyData>::New ();
00314 vtk_model->DeepCopy (static_cast<vtkPolyData*> (acc_hypo->obj_model_->getUserData ()));
00315
00316
00317 vtkSmartPointer<vtkMatrix4x4> vtk_mat = vtkSmartPointer<vtkMatrix4x4>::New ();
00318 vtk_mat->Identity ();
00319 arrayToVtkMatrix (acc_hypo->rigid_transform_, vtk_mat);
00320
00321 vtkSmartPointer<vtkTransform> vtk_transform = vtkSmartPointer<vtkTransform>::New ();
00322 vtk_transform->SetMatrix (vtk_mat);
00323
00324 vtkSmartPointer<vtkTransformPolyDataFilter> vtk_transformator = vtkSmartPointer<vtkTransformPolyDataFilter>::New ();
00325 vtk_transformator->SetTransform (vtk_transform);
00326 vtk_transformator->SetInput (vtk_model);
00327 vtk_transformator->Update ();
00328
00329
00330 vtkSmartPointer<vtkActor> vtk_actor = vtkSmartPointer<vtkActor>::New();
00331 vtkSmartPointer<vtkPolyDataMapper> vtk_mapper = vtkSmartPointer<vtkPolyDataMapper>::New ();
00332 vtk_mapper->SetInput(vtk_transformator->GetOutput ());
00333 vtk_actor->SetMapper(vtk_mapper);
00334
00335 vtk_actor->GetProperty ()->SetColor (0.6, 0.7, 0.9);
00336 renderer->AddActor(vtk_actor);
00337 params->model_actors_.push_back (vtk_actor);
00338
00339
00340 cout << acc_hypo->obj_model_->getObjectName () << "_" << i+1 << " has a confidence value of " << acc_hypo->match_confidence_ << "; ";
00341 }
00342
00343
00344 const float* ob = params->objrec_.getSceneOctree ().getBounds ();
00345 params->viz_.addCube (ob[0], ob[1], ob[2], ob[3], ob[4], ob[5], 1.0, 1.0, 1.0);
00346
00347 #if 0
00348
00349 float angle = static_cast<float> (aux::getRandomInteger (0, 100));
00350 angle -= AUX_PI_FLOAT*std::floor (angle/AUX_PI_FLOAT);
00351
00352
00353 Eigen::Matrix<float,3,1> axis;
00354 axis(0,0) = static_cast<float> (aux::getRandomInteger (-100, 100));
00355 axis(1,0) = static_cast<float> (aux::getRandomInteger (-100, 100));
00356 axis(2,0) = static_cast<float> (aux::getRandomInteger (-100, 100));
00357
00358 float len = std::sqrt (axis(0,0)*axis(0,0) + axis(1,0)*axis(1,0) + axis(2,0)*axis(2,0));
00359 axis(0,0) = axis(0,0)/len;
00360 axis(1,0) = axis(1,0)/len;
00361 axis(2,0) = axis(2,0)/len;
00362
00363 cout << "Input angle = " << angle << endl;
00364 cout << "Input axis = \n" << axis << endl;
00365
00366
00367 Eigen::AngleAxis<float> angle_axis(angle, axis);
00368
00369 Eigen::Matrix<float,3,3> mat = angle_axis.toRotationMatrix ();
00370 float m[9];
00371 aux::eigenMatrix3x3ToArray9RowMajor (mat, m);
00372
00373
00374 float comp_angle, comp_axis[3];
00375 aux::rotationMatrixToAxisAngle (m, comp_axis, comp_angle);
00376 cout << "\nComputed angle = " << comp_angle << endl;
00377 cout << "Computed axis = \n" << comp_axis[0] << "\n" << comp_axis[1] << "\n" << comp_axis[2] << endl;
00378 #endif
00379 }
00380
00381
00382
00383 void
00384 keyboardCB (const pcl::visualization::KeyboardEvent &event, void* params_void)
00385 {
00386 CallbackParameters* params = static_cast<CallbackParameters*> (params_void);
00387
00388 if (event.getKeyCode () == 13 && event.keyUp ())
00389 update (params);
00390 else if ( event.getKeyCode () == '1' && event.keyUp () )
00391 {
00392
00393 params->show_models_ = !params->show_models_;
00394
00395 for ( list<vtkActor*>::iterator it = params->model_actors_.begin () ; it != params->model_actors_.end () ; ++it )
00396 (*it)->SetVisibility (static_cast<int> (params->show_models_));
00397
00398 params->viz_.getRenderWindow ()->Render ();
00399 }
00400 }
00401
00402
00403
00404 void
00405 run (float pair_width, float voxel_size, float max_coplanarity_angle, int num_hypotheses_to_show)
00406 {
00407 PointCloud<PointXYZ>::Ptr scene_points (new PointCloud<PointXYZ> ()), model_points (new PointCloud<PointXYZ> ());
00408 PointCloud<Normal>::Ptr scene_normals (new PointCloud<Normal> ()), model_normals (new PointCloud<Normal> ());
00409
00410
00411 if ( !vtk_to_pointcloud ("../../test/tum_table_scene.vtk", *scene_points, *scene_normals) )
00412 return;
00413
00414 vtkPolyData *vtk_model = vtkPolyData::New ();
00415
00416 if ( !vtk_to_pointcloud ("../../test/tum_amicelli_box.vtk", *model_points, *model_normals, vtk_model) )
00417 return;
00418
00419
00420 ObjRecRANSAC objrec (pair_width, voxel_size);
00421 objrec.setMaxCoplanarityAngleDegrees (max_coplanarity_angle);
00422 objrec.addModel (*model_points, *model_normals, "amicelli", vtk_model);
00423
00424 objrec.enterTestModeTestHypotheses ();
00425
00426
00427 PCLVisualizer viz;
00428
00429 CallbackParameters params(objrec, viz, *scene_points, *scene_normals, num_hypotheses_to_show);
00430 viz.registerKeyboardCallback (keyboardCB, static_cast<void*> (¶ms));
00431
00432
00433 update (¶ms);
00434
00435 #ifdef _SHOW_SCENE_POINTS_
00436 viz.addPointCloud (scene_points, "cloud in");
00437 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "cloud in");
00438 #endif
00439
00440 #ifdef _SHOW_OCTREE_POINTS_
00441 PointCloud<PointXYZ>::Ptr octree_points (new PointCloud<PointXYZ> ());
00442 objrec.getSceneOctree ().getFullLeavesPoints (*octree_points);
00443 viz.addPointCloud (octree_points, "octree points");
00444 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 5, "octree points");
00445 viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, "octree points");
00446 #endif
00447
00448 #if defined _SHOW_OCTREE_NORMALS_ && defined _SHOW_OCTREE_POINTS_
00449 PointCloud<Normal>::Ptr octree_normals (new PointCloud<Normal> ());
00450 objrec.getSceneOctree ().getNormalsOfFullLeaves (*octree_normals);
00451 viz.addPointCloudNormals<PointXYZ,Normal> (octree_points, octree_normals, 1, 6.0f, "normals out");
00452 #endif
00453
00454
00455 while (!viz.wasStopped ())
00456 {
00457
00458 viz.spinOnce (100);
00459 boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00460 }
00461
00462 vtk_model->Delete ();
00463 }
00464
00465
00466
00467 int
00468 main (int argc, char** argv)
00469 {
00470 printf ("\nUsage: ./obj_rec_ransac_accepted_hypotheses <pair_width> <voxel_size> <max_coplanarity_angle> <n_hypotheses_to_show> <show_hypotheses_as_coordinate_frames>\n\n");
00471
00472 const int num_params = 4;
00473 float parameters[num_params] = {40.0f, 5.0f, 15.0f, 1};
00474 string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle", "n_hypotheses_to_show"};
00475
00476
00477 for ( int i = 0 ; i < argc-1 && i < num_params ; ++i )
00478 parameters[i] = static_cast<float> (atof (argv[i+1]));
00479
00480 printf ("The following parameter values will be used:\n");
00481 for ( int i = 0 ; i < num_params ; ++i )
00482 cout << " " << parameter_names[i] << " = " << parameters[i] << endl;
00483 cout << endl;
00484
00485 run (parameters[0], parameters[1], parameters[2], static_cast<int> (parameters[3] + 0.5f));
00486
00487 return (0);
00488 }
00489
00490