render_views_tesselated_sphere.cpp
Go to the documentation of this file.
00001 /*
00002  * render_views_tesselated_sphere.cpp
00003  *
00004  *  Created on: Dec 23, 2011
00005  *      Author: aitor
00006  */
00007 #include <pcl/point_types.h>
00008 #include <pcl/apps/render_views_tesselated_sphere.h>
00009 #include <vtkCellData.h>
00010 #include <vtkWorldPointPicker.h>
00011 #include <vtkPropPicker.h>
00012 #include <vtkPlatonicSolidSource.h>
00013 #include <vtkLoopSubdivisionFilter.h>
00014 #include <vtkTriangle.h>
00015 #include <vtkTransform.h>
00016 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>4)
00017 #include <vtkHardwareSelector.h>
00018 #include <vtkSelectionNode.h>
00019 #else 
00020 #include <vtkVisibleCellSelector.h>
00021 #endif
00022 #include <vtkSelection.h>
00023 #include <vtkCellArray.h>
00024 #include <vtkTransformFilter.h>
00025 #include <vtkCamera.h>
00026 #include <vtkActor.h>
00027 #include <vtkRenderWindow.h>
00028 #include <vtkRenderer.h>
00029 #include <vtkPolyDataMapper.h>
00030 #include <vtkPointPicker.h>
00031 
00032 void
00033 pcl::apps::RenderViewsTesselatedSphere::generateViews() {
00034   //center object
00035   double CoM[3];
00036   vtkIdType npts_com = 0, *ptIds_com = NULL;
00037   vtkSmartPointer<vtkCellArray> cells_com = polydata_->GetPolys ();
00038 
00039   double center[3], p1_com[3], p2_com[3], p3_com[3], area_com, totalArea_com = 0;
00040   double comx = 0, comy = 0, comz = 0;
00041   for (cells_com->InitTraversal (); cells_com->GetNextCell (npts_com, ptIds_com);)
00042   {
00043     polydata_->GetPoint (ptIds_com[0], p1_com);
00044     polydata_->GetPoint (ptIds_com[1], p2_com);
00045     polydata_->GetPoint (ptIds_com[2], p3_com);
00046     vtkTriangle::TriangleCenter (p1_com, p2_com, p3_com, center);
00047     area_com = vtkTriangle::TriangleArea (p1_com, p2_com, p3_com);
00048     comx += center[0] * area_com;
00049     comy += center[1] * area_com;
00050     comz += center[2] * area_com;
00051     totalArea_com += area_com;
00052   }
00053 
00054   CoM[0] = comx / totalArea_com;
00055   CoM[1] = comy / totalArea_com;
00056   CoM[2] = comz / totalArea_com;
00057 
00058   vtkSmartPointer<vtkTransform> trans_center = vtkSmartPointer<vtkTransform>::New ();
00059   trans_center->Translate (-CoM[0], -CoM[1], -CoM[2]);
00060   vtkSmartPointer<vtkMatrix4x4> matrixCenter = trans_center->GetMatrix ();
00061 
00062   vtkSmartPointer<vtkTransformFilter> trans_filter_center = vtkSmartPointer<vtkTransformFilter>::New ();
00063   trans_filter_center->SetTransform (trans_center);
00064   trans_filter_center->SetInput (polydata_);
00065   trans_filter_center->Update ();
00066 
00067   vtkSmartPointer<vtkPolyDataMapper> mapper = vtkSmartPointer<vtkPolyDataMapper>::New ();
00068   mapper->SetInputConnection (trans_filter_center->GetOutputPort ());
00069   mapper->Update ();
00070 
00071   //scale so it fits in the unit sphere!
00072   double bb[6];
00073   mapper->GetBounds (bb);
00074   double ms = (std::max) ((std::fabs) (bb[0] - bb[1]),
00075                           (std::max) ((std::fabs) (bb[2] - bb[3]), (std::fabs) (bb[4] - bb[5])));
00076   double max_side = radius_sphere_ / 2.0;
00077   double scale_factor = max_side / ms;
00078 
00079   vtkSmartPointer<vtkTransform> trans_scale = vtkSmartPointer<vtkTransform>::New ();
00080   trans_scale->Scale (scale_factor, scale_factor, scale_factor);
00081   vtkSmartPointer<vtkMatrix4x4> matrixScale = trans_scale->GetMatrix ();
00082 
00083   vtkSmartPointer<vtkTransformFilter> trans_filter_scale = vtkSmartPointer<vtkTransformFilter>::New ();
00084   trans_filter_scale->SetTransform (trans_scale);
00085   trans_filter_scale->SetInputConnection (trans_filter_center->GetOutputPort ());
00086   trans_filter_scale->Update ();
00087 
00088   mapper->SetInputConnection (trans_filter_scale->GetOutputPort ());
00089   mapper->Update ();
00090 
00092   // * Compute area of the mesh
00094   vtkSmartPointer<vtkCellArray> cells = mapper->GetInput ()->GetPolys ();
00095   vtkIdType npts = 0, *ptIds = NULL;
00096 
00097   double p1[3], p2[3], p3[3], area, totalArea = 0;
00098   for (cells->InitTraversal (); cells->GetNextCell (npts, ptIds);)
00099   {
00100     polydata_->GetPoint (ptIds[0], p1);
00101     polydata_->GetPoint (ptIds[1], p2);
00102     polydata_->GetPoint (ptIds[2], p3);
00103     area = vtkTriangle::TriangleArea (p1, p2, p3);
00104     totalArea += area;
00105   }
00106 
00107   //create icosahedron
00108   vtkSmartPointer<vtkPlatonicSolidSource> ico = vtkSmartPointer<vtkPlatonicSolidSource>::New ();
00109   ico->SetSolidTypeToIcosahedron ();
00110   ico->Update ();
00111 
00112   //tesselate cells from icosahedron
00113   vtkSmartPointer<vtkLoopSubdivisionFilter> subdivide = vtkSmartPointer<vtkLoopSubdivisionFilter>::New ();
00114   subdivide->SetNumberOfSubdivisions (tesselation_level_);
00115   subdivide->SetInputConnection (ico->GetOutputPort ());
00116 
00117   // Get camera positions
00118   vtkPolyData *sphere = subdivide->GetOutput ();
00119   sphere->Update ();
00120 
00121   std::vector<Eigen::Vector3f> cam_positions;
00122   if (!use_vertices_)
00123   {
00124     vtkSmartPointer<vtkCellArray> cells_sphere = sphere->GetPolys ();
00125     cam_positions.resize (sphere->GetNumberOfPolys ());
00126 
00127     size_t i=0;
00128     for (cells_sphere->InitTraversal (); cells_sphere->GetNextCell (npts_com, ptIds_com);)
00129     {
00130       sphere->GetPoint (ptIds_com[0], p1_com);
00131       sphere->GetPoint (ptIds_com[1], p2_com);
00132       sphere->GetPoint (ptIds_com[2], p3_com);
00133       vtkTriangle::TriangleCenter (p1_com, p2_com, p3_com, center);
00134       cam_positions[i] = Eigen::Vector3f (float (center[0]), float (center[1]), float (center[2]));
00135       i++;
00136     }
00137 
00138   }
00139   else
00140   {
00141     cam_positions.resize (sphere->GetNumberOfPoints ());
00142     for (int i = 0; i < sphere->GetNumberOfPoints (); i++)
00143     {
00144       double cam_pos[3];
00145       sphere->GetPoint (i, cam_pos);
00146       cam_positions[i] = Eigen::Vector3f (float (cam_pos[0]), float (cam_pos[1]), float (cam_pos[2]));
00147     }
00148   }
00149 
00150   /*int valid = 0;
00151   for (size_t i = 0; i < cam_positions.size (); i++)
00152   {
00153     if (campos_constraints_func_ (cam_positions[i]))
00154     {
00155       cam_positions[valid] = cam_positions[i];
00156       valid++;
00157     }
00158   }
00159 
00160   cam_positions.resize (valid);*/
00161 
00162   double camera_radius = radius_sphere_;
00163   double cam_pos[3];
00164   double first_cam_pos[3];
00165 
00166   first_cam_pos[0] = cam_positions[0][0] * radius_sphere_;
00167   first_cam_pos[1] = cam_positions[0][1] * radius_sphere_;
00168   first_cam_pos[2] = cam_positions[0][2] * radius_sphere_;
00169 
00170   //create renderer and window
00171   vtkSmartPointer<vtkRenderWindow> render_win = vtkSmartPointer<vtkRenderWindow>::New ();
00172   vtkSmartPointer<vtkRenderer> renderer = vtkSmartPointer<vtkRenderer>::New ();
00173   render_win->AddRenderer (renderer);
00174   render_win->SetSize (resolution_, resolution_);
00175   renderer->SetBackground (1.0, 0, 0);
00176 
00177   //create picker
00178   vtkSmartPointer<vtkWorldPointPicker> worldPicker = vtkSmartPointer<vtkWorldPointPicker>::New ();
00179 
00180   vtkSmartPointer<vtkCamera> cam = vtkSmartPointer<vtkCamera>::New ();
00181   cam->SetFocalPoint (0, 0, 0);
00182 
00183   Eigen::Vector3f cam_pos_3f = cam_positions[0];
00184   Eigen::Vector3f perp = cam_pos_3f.cross (Eigen::Vector3f::UnitY ());
00185   cam->SetViewUp (perp[0], perp[1], perp[2]);
00186 
00187   cam->SetPosition (first_cam_pos);
00188   cam->SetViewAngle (view_angle_);
00189   cam->Modified ();
00190 
00191   //For each camera position, traposesnsform the object and render view
00192   for (size_t i = 0; i < cam_positions.size (); i++)
00193   {
00194     cam_pos[0] = cam_positions[i][0];
00195     cam_pos[1] = cam_positions[i][1];
00196     cam_pos[2] = cam_positions[i][2];
00197 
00198     //create temporal virtual camera
00199     vtkSmartPointer<vtkCamera> cam_tmp = vtkSmartPointer<vtkCamera>::New ();
00200     cam_tmp->SetViewAngle (view_angle_);
00201 
00202     Eigen::Vector3f cam_pos_3f (static_cast<float> (cam_pos[0]), static_cast<float> (cam_pos[1]), static_cast<float> (cam_pos[2]));
00203     cam_pos_3f = cam_pos_3f.normalized ();
00204     Eigen::Vector3f test = Eigen::Vector3f::UnitY ();
00205 
00206     //If the view up is parallel to ray cam_pos - focalPoint then the transformation
00207     //is singular and no points are rendered...
00208     //make sure it is perpendicular
00209     if (fabs (cam_pos_3f.dot (test)) == 1)
00210     {
00211       //parallel, create
00212       test = cam_pos_3f.cross (Eigen::Vector3f::UnitX ());
00213     }
00214 
00215     cam_tmp->SetViewUp (test[0], test[1], test[2]);
00216 
00217     for (int k = 0; k < 3; k++)
00218     {
00219       cam_pos[k] = cam_pos[k] * camera_radius;
00220     }
00221 
00222     cam_tmp->SetPosition (cam_pos);
00223     cam_tmp->SetFocalPoint (0, 0, 0);
00224     cam_tmp->Modified ();
00225 
00226     //rotate model so it looks the same as if we would look from the new position
00227     vtkSmartPointer<vtkMatrix4x4> view_trans_inverted = vtkSmartPointer<vtkMatrix4x4>::New ();
00228     vtkMatrix4x4::Invert (cam->GetViewTransformMatrix (), view_trans_inverted);
00229     vtkSmartPointer<vtkTransform> trans_rot_pose = vtkSmartPointer<vtkTransform>::New ();
00230     trans_rot_pose->Identity ();
00231     trans_rot_pose->Concatenate (view_trans_inverted);
00232     trans_rot_pose->Concatenate (cam_tmp->GetViewTransformMatrix ());
00233     vtkSmartPointer<vtkTransformFilter> trans_rot_pose_filter = vtkSmartPointer<vtkTransformFilter>::New ();
00234     trans_rot_pose_filter->SetTransform (trans_rot_pose);
00235     trans_rot_pose_filter->SetInputConnection (trans_filter_scale->GetOutputPort ());
00236 
00237     //translate model so we can place camera at (0,0,0)
00238     vtkSmartPointer<vtkTransform> translation = vtkSmartPointer<vtkTransform>::New ();
00239     translation->Translate (first_cam_pos[0] * -1, first_cam_pos[1] * -1, first_cam_pos[2] * -1);
00240     vtkSmartPointer<vtkTransformFilter> translation_filter = vtkSmartPointer<vtkTransformFilter>::New ();
00241     translation_filter->SetTransform (translation);
00242     translation_filter->SetInputConnection (trans_rot_pose_filter->GetOutputPort ());
00243 
00244     //modify camera
00245     cam_tmp->SetPosition (0, 0, 0);
00246     cam_tmp->SetFocalPoint (first_cam_pos[0] * -1, first_cam_pos[1] * -1, first_cam_pos[2] * -1);
00247     cam_tmp->Modified ();
00248 
00249     //notice transformations for final pose
00250     vtkSmartPointer<vtkMatrix4x4> matrixRotModel = trans_rot_pose->GetMatrix ();
00251     vtkSmartPointer<vtkMatrix4x4> matrixTranslation = translation->GetMatrix ();
00252 
00253     mapper->SetInputConnection (translation_filter->GetOutputPort ());
00254     mapper->Update ();
00255 
00256     //render view
00257     vtkSmartPointer<vtkActor> actor_view = vtkSmartPointer<vtkActor>::New ();
00258     actor_view->SetMapper (mapper);
00259     renderer->SetActiveCamera (cam_tmp);
00260     renderer->AddActor (actor_view);
00261     renderer->Modified ();
00262     //renderer->ResetCameraClippingRange ();
00263     render_win->Render ();
00264 
00265     //back to real scale transform
00266     vtkSmartPointer<vtkTransform> backToRealScale = vtkSmartPointer<vtkTransform>::New ();
00267     backToRealScale->PostMultiply ();
00268     backToRealScale->Identity ();
00269     backToRealScale->Concatenate (matrixScale);
00270     backToRealScale->Concatenate (matrixTranslation);
00271     backToRealScale->Inverse ();
00272     backToRealScale->Modified ();
00273     backToRealScale->Concatenate (matrixTranslation);
00274     backToRealScale->Modified ();
00275 
00276     Eigen::Matrix4f backToRealScale_eigen;
00277     backToRealScale_eigen.setIdentity ();
00278 
00279     for (int x = 0; x < 4; x++)
00280       for (int y = 0; y < 4; y++)
00281         backToRealScale_eigen (x, y) = float (backToRealScale->GetMatrix ()->GetElement (x, y));
00282 
00283     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00284     cloud->points.resize (resolution_ * resolution_);
00285 
00286     if (gen_organized_)
00287     {
00288       cloud->width = resolution_;
00289       cloud->height = resolution_;
00290       cloud->is_dense = false;
00291 
00292       double coords[3];
00293       float * depth = new float[resolution_ * resolution_];
00294       render_win->GetZbufferData (0, 0, resolution_ - 1, resolution_ - 1, &(depth[0]));
00295 
00296       for (int x = 0; x < resolution_; x++)
00297       {
00298         for (int y = 0; y < resolution_; y++)
00299         {
00300           float value = depth[y * resolution_ + x];
00301           if (value == 1.0)
00302           {
00303             cloud->at (y, x).x = cloud->at (y, x).y = cloud->at (y, x).z = std::numeric_limits<float>::quiet_NaN ();
00304           }
00305           else
00306           {
00307             worldPicker->Pick (x, y, value, renderer);
00308             worldPicker->GetPickPosition (coords);
00309             cloud->at (y, x).x = static_cast<float> (coords[0]);
00310             cloud->at (y, x).y = static_cast<float> (coords[1]);
00311             cloud->at (y, x).z = static_cast<float> (coords[2]);
00312             cloud->at (y, x).getVector4fMap () = backToRealScale_eigen
00313                                   * cloud->at (y, x).getVector4fMap ();
00314           }
00315         }
00316       }
00317 
00318       delete[] depth;
00319 
00320     }
00321     else
00322     {
00323       cloud->width = resolution_ * resolution_;
00324       cloud->height = 1;
00325 
00326       double coords[3];
00327       float * depth = new float[resolution_ * resolution_];
00328       render_win->GetZbufferData (0, 0, resolution_ - 1, resolution_ - 1, &(depth[0]));
00329 
00330       int count_valid_depth_pixels = 0;
00331       for (int x = 0; x < resolution_; x++)
00332       {
00333         for (int y = 0; y < resolution_; y++)
00334         {
00335           float value = depth[y * resolution_ + x];
00336           if (value == 1.0)
00337             continue;
00338 
00339           worldPicker->Pick (x, y, value, renderer);
00340           worldPicker->GetPickPosition (coords);
00341           cloud->points[count_valid_depth_pixels].x = static_cast<float> (coords[0]);
00342           cloud->points[count_valid_depth_pixels].y = static_cast<float> (coords[1]);
00343           cloud->points[count_valid_depth_pixels].z = static_cast<float> (coords[2]);
00344           cloud->points[count_valid_depth_pixels].getVector4fMap () = backToRealScale_eigen
00345                       * cloud->points[count_valid_depth_pixels].getVector4fMap ();
00346           count_valid_depth_pixels++;
00347         }
00348       }
00349 
00350       delete[] depth;
00351 
00352       cloud->points.resize (count_valid_depth_pixels);
00353       cloud->width = count_valid_depth_pixels;
00354     }
00355 
00356     if(compute_entropy_) {
00358       // * Compute area of the mesh
00360 
00361       vtkSmartPointer<vtkPolyData> polydata = mapper->GetInput ();
00362       polydata->BuildCells ();
00363 
00364       vtkSmartPointer<vtkCellArray> cells = polydata->GetPolys ();
00365       vtkIdType npts = 0, *ptIds = NULL;
00366 
00367       double p1[3], p2[3], p3[3], area, totalArea = 0;
00368       for (cells->InitTraversal (); cells->GetNextCell (npts, ptIds);)
00369       {
00370         polydata->GetPoint (ptIds[0], p1);
00371         polydata->GetPoint (ptIds[1], p2);
00372         polydata->GetPoint (ptIds[2], p3);
00373         area = vtkTriangle::TriangleArea (p1, p2, p3);
00374         totalArea += area;
00375       }
00376 
00378       // * Select visible cells (triangles)
00380 #if (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION<6)
00381       vtkSmartPointer<vtkVisibleCellSelector> selector = vtkSmartPointer<vtkVisibleCellSelector>::New ();
00382       vtkSmartPointer<vtkIdTypeArray> selection = vtkSmartPointer<vtkIdTypeArray>::New ();
00383 
00384       selector->SetRenderer (renderer);
00385       selector->SetArea (0, 0, resolution_ - 1, resolution_ - 1);
00386       selector->Select ();
00387       selector->GetSelectedIds (selection);
00388 
00389       double visible_area = 0;
00390       for (int sel_id = 3; sel_id < (selection->GetNumberOfTuples () * selection->GetNumberOfComponents ()); sel_id
00391           += selection->GetNumberOfComponents ())
00392       {
00393         int id_mesh = int (selection->GetValue (sel_id));
00394 
00395         if (id_mesh >= polydata->GetNumberOfCells ())
00396           continue;
00397 
00398         vtkCell * cell = polydata->GetCell (id_mesh);
00399         vtkTriangle* triangle = dynamic_cast<vtkTriangle*> (cell);
00400         double p0[3];
00401         double p1[3];
00402         double p2[3];
00403         triangle->GetPoints ()->GetPoint (0, p0);
00404         triangle->GetPoints ()->GetPoint (1, p1);
00405         triangle->GetPoints ()->GetPoint (2, p2);
00406         visible_area += vtkTriangle::TriangleArea (p0, p1, p2);
00407       }
00408 
00409 #else 
00410       vtkSmartPointer<vtkHardwareSelector> hardware_selector = vtkSmartPointer<vtkHardwareSelector>::New ();
00411       hardware_selector->ClearBuffers();
00412       vtkSmartPointer<vtkSelection> hdw_selection = vtkSmartPointer<vtkSelection>::New ();
00413       hardware_selector->SetRenderer (renderer);
00414       hardware_selector->SetArea (0, 0, resolution_ - 1, resolution_ - 1);
00415       hardware_selector->SetFieldAssociation(vtkDataObject::FIELD_ASSOCIATION_CELLS);
00416       hdw_selection = hardware_selector->Select ();
00417       vtkSmartPointer<vtkIdTypeArray> ids = vtkSmartPointer<vtkIdTypeArray>::New ();
00418       ids = vtkIdTypeArray::SafeDownCast(hdw_selection->GetNode(0)->GetSelectionList());
00419       double visible_area = 0;
00420       for (int sel_id = 0; sel_id < (ids->GetNumberOfTuples ()); sel_id++)
00421       {
00422         int id_mesh = int (ids->GetValue (sel_id));
00423         if(id_mesh >= polydata->GetNumberOfPolys())
00424           continue;
00425 
00426         vtkCell * cell = polydata->GetCell (id_mesh);
00427         vtkTriangle* triangle = dynamic_cast<vtkTriangle*> (cell);
00428         double p0[3];
00429         double p1[3];
00430         double p2[3];
00431         triangle->GetPoints ()->GetPoint (0, p0);
00432         triangle->GetPoints ()->GetPoint (1, p1);
00433         triangle->GetPoints ()->GetPoint (2, p2);
00434         area = vtkTriangle::TriangleArea (p0, p1, p2);
00435         visible_area += area;
00436       }
00437 #endif
00438 
00439       entropies_.push_back (float (visible_area / totalArea));
00440     }
00441 
00442     //transform cloud to give camera coordinates instead of world coordinates!
00443     vtkSmartPointer<vtkMatrix4x4> view_transform = cam_tmp->GetViewTransformMatrix ();
00444     Eigen::Matrix4f trans_view;
00445     trans_view.setIdentity ();
00446 
00447     for (int x = 0; x < 4; x++)
00448       for (int y = 0; y < 4; y++)
00449         trans_view (x, y) = float (view_transform->GetElement (x, y));
00450 
00451     //NOTE: vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right)
00452     //thus, the fliping in y and z
00453     for (size_t i = 0; i < cloud->points.size (); i++)
00454     {
00455       cloud->points[i].getVector4fMap () = trans_view * cloud->points[i].getVector4fMap ();
00456       cloud->points[i].y *= -1.0f;
00457       cloud->points[i].z *= -1.0f;
00458     }
00459 
00460     renderer->RemoveActor (actor_view);
00461 
00462     generated_views_.push_back (cloud);
00463 
00464     //create pose, from OBJECT coordinates to CAMERA coordinates!
00465     vtkSmartPointer<vtkTransform> transOCtoCC = vtkSmartPointer<vtkTransform>::New ();
00466     transOCtoCC->PostMultiply ();
00467     transOCtoCC->Identity ();
00468     transOCtoCC->Concatenate (matrixCenter);
00469     transOCtoCC->Concatenate (matrixRotModel);
00470     transOCtoCC->Concatenate (matrixTranslation);
00471     transOCtoCC->Concatenate (cam_tmp->GetViewTransformMatrix ());
00472 
00473     //NOTE: vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right)
00474     //thus, the fliping in y and z
00475     vtkSmartPointer<vtkMatrix4x4> cameraSTD = vtkSmartPointer<vtkMatrix4x4>::New ();
00476     cameraSTD->Identity ();
00477     cameraSTD->SetElement (0, 0, 1);
00478     cameraSTD->SetElement (1, 1, -1);
00479     cameraSTD->SetElement (2, 2, -1);
00480 
00481     transOCtoCC->Concatenate (cameraSTD);
00482     transOCtoCC->Modified ();
00483 
00484     Eigen::Matrix4f pose_view;
00485     pose_view.setIdentity ();
00486 
00487     for (int x = 0; x < 4; x++)
00488       for (int y = 0; y < 4; y++)
00489         pose_view (x, y) = float (transOCtoCC->GetMatrix ()->GetElement (x, y));
00490 
00491     poses_.push_back (pose_view);
00492 
00493   }
00494 }


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