obj_rec_ransac_scene_opps.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_scene_opps.cpp
00038  *
00039  *  Created on: Jan 17, 2013
00040  *      Author: papazov
00041  *
00042  *  Calls recognize() of the ObjRecRANSAC class and visualizes the oriented point pairs (opp) sampled from the scene.
00043  *  Does NOT perform full recognition.
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 <vtkDoubleArray.h>
00054 #include <vtkDataArray.h>
00055 #include <vtkPointData.h>
00056 #include <vtkHedgeHog.h>
00057 #include <cstdio>
00058 #include <vector>
00059 
00060 using namespace std;
00061 using namespace pcl;
00062 using namespace io;
00063 using namespace console;
00064 using namespace recognition;
00065 using namespace visualization;
00066 
00067 class CallbackParameters;
00068 
00069 void run (float pair_width, float voxel_size, float max_coplanarity_angle);
00070 bool vtk_to_pointcloud (const char* file_name, PointCloud<PointXYZ>& pcl_points, PointCloud<Normal>& pcl_normals);
00071 void update (CallbackParameters* params);
00072 
00073 //#define _SHOW_SCENE_POINTS_
00074 #define _SHOW_OCTREE_POINTS_
00075 //#define _SHOW_OCTREE_NORMALS_
00076 
00077 class CallbackParameters
00078 {
00079   public:
00080     CallbackParameters (ObjRecRANSAC& objrec, PCLVisualizer& viz, PointCloud<PointXYZ>& points, PointCloud<Normal>& normals)
00081     : objrec_ (objrec),
00082       viz_ (viz),
00083       points_ (points),
00084       normals_ (normals)
00085     { }
00086 
00087     ObjRecRANSAC& objrec_;
00088     PCLVisualizer& viz_;
00089     PointCloud<PointXYZ>& points_;
00090     PointCloud<Normal>& normals_;
00091 };
00092 
00093 //===========================================================================================================================================
00094 
00095 int
00096 main (int argc, char** argv)
00097 {
00098   printf ("\nUsage: ./pcl_obj_rec_ransac_scene_opps <pair_width> <voxel_size> <max_coplanarity_angle>\n\n");
00099 
00100   const int num_params = 3;
00101   float parameters[num_params] = {40.0f/*pair width*/, 5.0f/*voxel size*/, 15.0f/*max co-planarity angle*/};
00102   string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"};
00103 
00104   // Read the user input if any
00105   for ( int i = 0 ; i < argc-1 && i < num_params ; ++i )
00106   {
00107     parameters[i] = static_cast<float> (atof (argv[i+1]));
00108     if ( parameters[i] <= 0.0f )
00109     {
00110       fprintf(stderr, "ERROR: the %i-th parameter has to be positive and not %f\n", i+1, parameters[i]);
00111       return (-1);
00112     }
00113   }
00114 
00115   printf ("The following parameter values will be used:\n");
00116   for ( int i = 0 ; i < num_params ; ++i )
00117     cout << "  " << parameter_names[i] << " = " << parameters[i] << endl;
00118   cout << endl;
00119 
00120   run (parameters[0], parameters[1], parameters[2]);
00121 
00122   return (0);
00123 }
00124 
00125 //===============================================================================================================================
00126 
00127 void keyboardCB (const pcl::visualization::KeyboardEvent &event, void* params_void)
00128 {
00129   if (event.getKeyCode () == 13 /*enter*/ && event.keyUp ())
00130     update (static_cast<CallbackParameters*> (params_void));
00131 }
00132 
00133 //===============================================================================================================================
00134 
00135 void update (CallbackParameters* params)
00136 {
00137   list<ObjRecRANSAC::Output> dummy_output;
00138 
00139   // Run the recognition method
00140   params->objrec_.recognize (params->points_, params->normals_, dummy_output);
00141 
00142   // Build the vtk objects visualizing the lines between the opps
00143   const list<ObjRecRANSAC::OrientedPointPair>& opps = params->objrec_.getSampledOrientedPointPairs ();
00144   cout << "There is (are) " << opps.size () << " oriented point pair(s).\n";
00145   // The opps points
00146   vtkSmartPointer<vtkPolyData> vtk_opps = vtkSmartPointer<vtkPolyData>::New ();
00147   vtkSmartPointer<vtkPoints> vtk_opps_points = vtkSmartPointer<vtkPoints>::New ();
00148     vtk_opps_points->SetNumberOfPoints (2*static_cast<vtkIdType> (opps.size ()));
00149   vtkSmartPointer<vtkCellArray> vtk_opps_lines = vtkSmartPointer<vtkCellArray>::New ();
00150   // The opps normals
00151   vtkSmartPointer<vtkDoubleArray> vtk_normals = vtkSmartPointer<vtkDoubleArray>::New ();
00152   vtk_normals->SetNumberOfComponents (3);
00153   vtk_normals->SetNumberOfTuples (2*static_cast<vtkIdType> (opps.size ()));
00154   vtkIdType ids[2] = {0, 1};
00155 
00156   // Insert the points and compute the lines
00157   for ( list<ObjRecRANSAC::OrientedPointPair>::const_iterator it = opps.begin () ; it != opps.end () ; ++it )
00158   {
00159     vtk_opps_points->SetPoint (ids[0], it->p1_[0], it->p1_[1], it->p1_[2]);
00160     vtk_opps_points->SetPoint (ids[1], it->p2_[0], it->p2_[1], it->p2_[2]);
00161     vtk_opps_lines->InsertNextCell (2, ids);
00162 
00163     vtk_normals->SetTuple3 (ids[0], it->n1_[0], it->n1_[1], it->n1_[2]);
00164     vtk_normals->SetTuple3 (ids[1], it->n2_[0], it->n2_[1], it->n2_[2]);
00165 
00166     ids[0] += 2;
00167     ids[1] += 2;
00168   }
00169   vtk_opps->SetPoints (vtk_opps_points);
00170   vtk_opps->GetPointData ()->SetNormals (vtk_normals);
00171   vtk_opps->SetLines (vtk_opps_lines);
00172 
00173   vtkSmartPointer<vtkHedgeHog> vtk_hh = vtkSmartPointer<vtkHedgeHog>::New ();
00174   vtk_hh->SetVectorModeToUseNormal ();
00175   vtk_hh->SetScaleFactor (0.5f*params->objrec_.getPairWidth ());
00176   vtk_hh->SetInput (vtk_opps);
00177   vtk_hh->Update ();
00178 
00179   // The lines
00180   string lines_str_id = "opps";
00181   params->viz_.removeShape(lines_str_id);
00182   params->viz_.addModelFromPolyData (vtk_opps, lines_str_id);
00183   params->viz_.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0.0, 0.0, 1.0, lines_str_id);
00184   // The normals
00185   string normals_str_id = "opps normals";
00186   params->viz_.removeShape(normals_str_id);
00187   params->viz_.addModelFromPolyData (vtk_hh->GetOutput (), normals_str_id);
00188   params->viz_.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 1.0, 0.0, normals_str_id);
00189 
00190 }
00191 
00192 //===============================================================================================================================
00193 
00194 void run (float pair_width, float voxel_size, float max_coplanarity_angle)
00195 {
00196   PointCloud<PointXYZ>::Ptr scene_points (new PointCloud<PointXYZ> ());
00197   PointCloud<Normal>::Ptr scene_normals (new PointCloud<Normal> ());
00198 
00199   // Get the points and normals from the input vtk file
00200   if ( !vtk_to_pointcloud ("../../test/tum_table_scene.vtk", *scene_points, *scene_normals) )
00201     return;
00202 
00203   // The recognition object
00204   ObjRecRANSAC objrec (pair_width, voxel_size);
00205   objrec.setMaxCoplanarityAngleDegrees (max_coplanarity_angle);
00206   // Switch to the test mode in which only oriented point pairs from the scene are sampled
00207   objrec.enterTestModeSampleOPP ();
00208 
00209   // The visualizer
00210   PCLVisualizer viz;
00211 
00212   CallbackParameters params(objrec, viz, *scene_points, *scene_normals);
00213   viz.registerKeyboardCallback (keyboardCB, static_cast<void*> (&params));
00214 
00215   // Run the recognition and update the viewer
00216   update (&params);
00217 
00218 #ifdef _SHOW_SCENE_POINTS_
00219   viz.addPointCloud (scene_points, "cloud in");
00220   viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "cloud in");
00221 #endif
00222 
00223 #ifdef _SHOW_OCTREE_POINTS_
00224   PointCloud<PointXYZ>::Ptr octree_points (new PointCloud<PointXYZ> ());
00225   objrec.getSceneOctree ().getFullLeavesPoints (*octree_points);
00226   viz.addPointCloud (octree_points, "octree points");
00227   viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 5, "octree points");
00228   viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, "octree points");
00229 #endif
00230 
00231 #if defined _SHOW_OCTREE_NORMALS_ && defined _SHOW_OCTREE_POINTS_
00232   PointCloud<Normal>::Ptr octree_normals (new PointCloud<Normal> ());
00233   objrec.getSceneOctree ().getNormalsOfFullLeaves (*octree_normals);
00234   viz.addPointCloudNormals<PointXYZ,Normal> (octree_points, octree_normals, 1, 6.0f, "normals out");
00235 #endif
00236 
00237   // Enter the main loop
00238   while (!viz.wasStopped ())
00239   {
00240     //main loop of the visualizer
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   // Load the model
00258   vtkSmartPointer<vtkPolyDataReader> reader = vtkSmartPointer<vtkPolyDataReader>::New ();
00259   reader->SetFileName (file_name);
00260   reader->Update ();
00261 
00262   // Get the points
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   // Copy the points
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   // Check if we have normals
00280   vtkDataArray *vtk_normals = vtk_poly->GetPointData ()->GetNormals ();
00281   if ( !vtk_normals )
00282     return false;
00283 
00284   pcl_normals.resize (num_points);
00285   // Copy the normals
00286   for ( vtkIdType i = 0 ; i < num_points ; ++i )
00287   {
00288     vtk_normals->GetTuple (i, p);
00289     pcl_normals[i].normal_x = static_cast<float> (p[0]);
00290     pcl_normals[i].normal_y = static_cast<float> (p[1]);
00291     pcl_normals[i].normal_z = static_cast<float> (p[2]);
00292   }
00293 
00294   return true;
00295 }
00296 
00297 //===============================================================================================================================


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