interactor_style.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 
00039 #include <list>
00040 #include <pcl/visualization/common/io.h>
00041 #include <pcl/visualization/interactor_style.h>
00042 #include <vtkLODActor.h>
00043 #include <vtkPolyData.h>
00044 #include <vtkPolyDataMapper.h>
00045 #include <vtkCellArray.h>
00046 #include <vtkTextProperty.h>
00047 #include <vtkAbstractPropPicker.h>
00048 #include <vtkCamera.h>
00049 #include <vtkRenderWindowInteractor.h>
00050 #include <vtkScalarBarActor.h>
00051 #include <vtkPNGWriter.h>
00052 #include <vtkWindowToImageFilter.h>
00053 #include <vtkRendererCollection.h>
00054 #include <vtkActorCollection.h>
00055 #include <vtkLegendScaleActor.h>
00056 #include <vtkRenderer.h>
00057 #include <vtkRenderWindow.h>
00058 #include <vtkObjectFactory.h>
00059 #include <vtkProperty.h>
00060 #include <vtkPointData.h>
00061 #include <vtkAssemblyPath.h>
00062 #include <vtkAbstractPicker.h>
00063 #include <vtkPointPicker.h>
00064 #include <vtkAreaPicker.h>
00065 
00066 #include <pcl/visualization/vtk/vtkVertexBufferObjectMapper.h>
00067 
00068 #define ORIENT_MODE 0
00069 #define SELECT_MODE 1
00070 
00072 void
00073 pcl::visualization::PCLVisualizerInteractorStyle::Initialize ()
00074 {
00075   modifier_ = pcl::visualization::INTERACTOR_KB_MOD_ALT;
00076   // Set windows size (width, height) to unknown (-1)
00077   win_height_ = win_width_ = -1;
00078   win_pos_x_ = win_pos_y_ = 0;
00079   max_win_height_ = max_win_width_ = -1;
00080 
00081   // Grid is disabled by default
00082   grid_enabled_ = false;
00083   grid_actor_ = vtkSmartPointer<vtkLegendScaleActor>::New ();
00084 
00085   // LUT is disabled by default
00086   lut_enabled_ = false;
00087   lut_actor_ = vtkSmartPointer<vtkScalarBarActor>::New ();
00088   lut_actor_->SetTitle ("");
00089   lut_actor_->SetOrientationToHorizontal ();
00090   lut_actor_->SetPosition (0.05, 0.01);
00091   lut_actor_->SetWidth (0.9);
00092   lut_actor_->SetHeight (0.1);
00093   lut_actor_->SetNumberOfLabels (lut_actor_->GetNumberOfLabels () * 2);
00094   vtkSmartPointer<vtkTextProperty> prop = lut_actor_->GetLabelTextProperty ();
00095   prop->SetFontSize (10);
00096   lut_actor_->SetLabelTextProperty (prop);
00097   lut_actor_->SetTitleTextProperty (prop);
00098 
00099   // Create the image filter and PNG writer objects
00100   wif_ = vtkSmartPointer<vtkWindowToImageFilter>::New ();
00101   snapshot_writer_ = vtkSmartPointer<vtkPNGWriter>::New ();
00102   snapshot_writer_->SetInputConnection (wif_->GetOutputPort ());
00103 
00104   init_ = true;
00105 
00106   stereo_anaglyph_mask_default_ = true;
00107 
00108   // Start in orient mode
00109   Superclass::CurrentMode = ORIENT_MODE;
00110 
00111   // Add our own mouse callback before any user callback. Used for accurate point picking.
00112   mouse_callback_ = vtkSmartPointer<pcl::visualization::PointPickingCallback>::New ();
00113   AddObserver (vtkCommand::LeftButtonPressEvent, mouse_callback_);
00114   AddObserver (vtkCommand::LeftButtonReleaseEvent, mouse_callback_);
00115 }
00116 
00118 void
00119 pcl::visualization::PCLVisualizerInteractorStyle::saveScreenshot (const std::string &file)
00120 {
00121   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00122   wif_->SetInput (Interactor->GetRenderWindow ());
00123   wif_->Modified ();      // Update the WindowToImageFilter
00124   snapshot_writer_->Modified ();
00125   snapshot_writer_->SetFileName (file.c_str ());
00126   snapshot_writer_->Write ();
00127 }
00128 
00130 void
00131 pcl::visualization::PCLVisualizerInteractorStyle::zoomIn ()
00132 {
00133   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00134   // Zoom in
00135   StartDolly ();
00136   double factor = 10.0 * 0.2 * .5;
00137   Dolly (pow (1.1, factor));
00138   EndDolly ();
00139 }
00140 
00142 void
00143 pcl::visualization::PCLVisualizerInteractorStyle::zoomOut ()
00144 {
00145   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00146   // Zoom out
00147   StartDolly ();
00148   double factor = 10.0 * -0.2 * .5;
00149   Dolly (pow (1.1, factor));
00150   EndDolly ();
00151 }
00152 
00154 void
00155 pcl::visualization::PCLVisualizerInteractorStyle::OnChar ()
00156 {
00157   // Make sure we ignore the same events we handle in OnKeyDown to avoid calling things twice
00158   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00159   if (Interactor->GetKeyCode () >= '0' && Interactor->GetKeyCode () <= '9')
00160     return;
00161   std::string key (Interactor->GetKeySym ());
00162   if (key.find ("XF86ZoomIn") != std::string::npos)
00163     zoomIn ();
00164   else if (key.find ("XF86ZoomOut") != std::string::npos)
00165     zoomOut ();
00166 
00167   bool keymod = false;
00168   switch (modifier_)
00169   {
00170     case INTERACTOR_KB_MOD_ALT:
00171     {
00172       keymod = Interactor->GetAltKey ();
00173       break;
00174     }
00175     case INTERACTOR_KB_MOD_CTRL:
00176     {
00177       keymod = Interactor->GetControlKey ();
00178       break;
00179     }
00180     case INTERACTOR_KB_MOD_SHIFT:
00181     {
00182       keymod = Interactor->GetShiftKey ();
00183       break;
00184     }
00185   }
00186 
00187   switch (Interactor->GetKeyCode ())
00188   {
00189     // All of the options below simply exit
00190     case 'h': case 'H':
00191     case 'l': case 'L':
00192     case 'p': case 'P':
00193     case 'j': case 'J':
00194     case 'c': case 'C':
00195     case 43:        // KEY_PLUS
00196     case 45:        // KEY_MINUS
00197     case 'f': case 'F':
00198     case 'g': case 'G':
00199     case 'o': case 'O':
00200     case 'u': case 'U':
00201     case 'q': case 'Q':
00202     case 'x': case 'X':
00203     case 'r': case 'R':
00204     {
00205       break;
00206     }
00207     // S have a special !ALT case
00208     case 's': case 'S':
00209     {
00210       if (!keymod)
00211         Superclass::OnChar ();
00212       break;
00213     }
00214     default:
00215     {
00216       Superclass::OnChar ();
00217       break;
00218     }
00219   }
00220 }
00221 
00223 boost::signals2::connection
00224 pcl::visualization::PCLVisualizerInteractorStyle::registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> callback)
00225 {
00226   return (mouse_signal_.connect (callback));
00227 }
00228 
00230 boost::signals2::connection
00231 pcl::visualization::PCLVisualizerInteractorStyle::registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> callback)
00232 {
00233   return (keyboard_signal_.connect (callback));
00234 }
00235 
00237 boost::signals2::connection
00238 pcl::visualization::PCLVisualizerInteractorStyle::registerPointPickingCallback (boost::function<void (const pcl::visualization::PointPickingEvent&)> callback)
00239 {
00240   return (point_picking_signal_.connect (callback));
00241 }
00242 
00244 boost::signals2::connection
00245 pcl::visualization::PCLVisualizerInteractorStyle::registerAreaPickingCallback (boost::function<void (const pcl::visualization::AreaPickingEvent&)> callback)
00246 {
00247   return (area_picking_signal_.connect (callback));
00248 }
00249 
00251 void
00252 pcl::visualization::PCLVisualizerInteractorStyle::OnKeyDown ()
00253 {
00254   if (!init_)
00255   {
00256     pcl::console::print_error ("[PCLVisualizerInteractorStyle] Interactor style not initialized. Please call Initialize () before continuing.\n");
00257     return;
00258   }
00259 
00260   if (!rens_)
00261   {
00262     pcl::console::print_error ("[PCLVisualizerInteractorStyle] No renderer collection given! Use SetRendererCollection () before continuing.\n");
00263     return;
00264   }
00265 
00266   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00267 
00268   if (wif_->GetInput () == NULL)
00269   {
00270     wif_->SetInput (Interactor->GetRenderWindow ());
00271     wif_->Modified ();
00272     snapshot_writer_->Modified ();
00273   }
00274 
00275   // Save the initial windows width/height
00276   if (win_height_ == -1 || win_width_ == -1)
00277   {
00278     int *win_size = Interactor->GetRenderWindow ()->GetSize ();
00279     win_height_ = win_size[0];
00280     win_width_  = win_size[1];
00281   }
00282 
00283   // Get the status of special keys (Cltr+Alt+Shift)
00284   bool shift = Interactor->GetShiftKey   ();
00285   bool ctrl  = Interactor->GetControlKey ();
00286   bool alt   = Interactor->GetAltKey ();
00287 
00288   bool keymod = false;
00289   switch (modifier_)
00290   {
00291     case INTERACTOR_KB_MOD_ALT:
00292     {
00293       keymod = alt;
00294       break;
00295     }
00296     case INTERACTOR_KB_MOD_CTRL:
00297     {
00298       keymod = ctrl;
00299       break;
00300     }
00301     case INTERACTOR_KB_MOD_SHIFT:
00302     {
00303       keymod = shift;
00304       break;
00305     }
00306   }
00307 
00308   // ---[ Check the rest of the key codes
00309 
00310   // Switch between point color/geometry handlers
00311   if (Interactor->GetKeySym () && Interactor->GetKeySym ()[0]  >= '0' && Interactor->GetKeySym ()[0] <= '9')
00312   {
00313     CloudActorMap::iterator it;
00314     int index = Interactor->GetKeySym ()[0] - '0' - 1;
00315     if (index == -1) index = 9;
00316 
00317     // Add 10 more for CTRL+0..9 keys
00318     if (ctrl)
00319       index += 10;
00320 
00321     // Geometry ?
00322     if (keymod)
00323     {
00324       for (it = actors_->begin (); it != actors_->end (); ++it)
00325       {
00326         CloudActor *act = &(*it).second;
00327         if (index >= static_cast<int> (act->geometry_handlers.size ()))
00328           continue;
00329 
00330         // Save the geometry handler index for later usage
00331         act->geometry_handler_index_ = index;
00332 
00333         // Create the new geometry
00334         PointCloudGeometryHandler<pcl::PCLPointCloud2>::ConstPtr geometry_handler = act->geometry_handlers[index];
00335 
00336         // Use the handler to obtain the geometry
00337         vtkSmartPointer<vtkPoints> points;
00338         geometry_handler->getGeometry (points);
00339 
00340         // Set the vertices
00341         vtkSmartPointer<vtkCellArray> vertices = vtkSmartPointer<vtkCellArray>::New ();
00342         for (vtkIdType i = 0; i < static_cast<vtkIdType> (points->GetNumberOfPoints ()); ++i)
00343           vertices->InsertNextCell (static_cast<vtkIdType>(1), &i);
00344 
00345         // Create the data
00346         vtkSmartPointer<vtkPolyData> data = vtkSmartPointer<vtkPolyData>::New ();
00347         data->SetPoints (points);
00348         data->SetVerts (vertices);
00349         // Modify the mapper
00350         if (use_vbos_)
00351         {
00352           vtkVertexBufferObjectMapper* mapper = static_cast<vtkVertexBufferObjectMapper*>(act->actor->GetMapper ());
00353           mapper->SetInput (data);
00354           // Modify the actor
00355           act->actor->SetMapper (mapper);
00356         }
00357         else
00358         {
00359           vtkPolyDataMapper* mapper = static_cast<vtkPolyDataMapper*>(act->actor->GetMapper ());
00360           mapper->SetInput (data);
00361           // Modify the actor
00362           act->actor->SetMapper (mapper);
00363         }
00364         act->actor->Modified ();
00365       }
00366     }
00367     else
00368     {
00369       for (it = actors_->begin (); it != actors_->end (); ++it)
00370       {
00371         CloudActor *act = &(*it).second;
00372         // Check for out of bounds
00373         if (index >= static_cast<int> (act->color_handlers.size ()))
00374           continue;
00375 
00376         // Save the color handler index for later usage
00377         act->color_handler_index_ = index;
00378 
00379         // Get the new color
00380         PointCloudColorHandler<pcl::PCLPointCloud2>::ConstPtr color_handler = act->color_handlers[index];
00381 
00382         vtkSmartPointer<vtkDataArray> scalars;
00383         color_handler->getColor (scalars);
00384         double minmax[2];
00385         scalars->GetRange (minmax);
00386         // Update the data
00387         vtkPolyData *data = static_cast<vtkPolyData*>(act->actor->GetMapper ()->GetInput ());
00388         data->GetPointData ()->SetScalars (scalars);
00389         data->Update ();
00390         // Modify the mapper
00391         if (use_vbos_)
00392         {
00393           vtkVertexBufferObjectMapper* mapper = static_cast<vtkVertexBufferObjectMapper*>(act->actor->GetMapper ());
00394           mapper->SetScalarRange (minmax);
00395           mapper->SetScalarModeToUsePointData ();
00396           mapper->SetInput (data);
00397           // Modify the actor
00398           act->actor->SetMapper (mapper);
00399         }
00400         else
00401         {
00402           vtkPolyDataMapper* mapper = static_cast<vtkPolyDataMapper*>(act->actor->GetMapper ());
00403           mapper->SetScalarRange (minmax);
00404           mapper->SetScalarModeToUsePointData ();
00405           mapper->SetInput (data);
00406           // Modify the actor
00407           act->actor->SetMapper (mapper);
00408         }
00409         act->actor->Modified ();
00410       }
00411     }
00412 
00413     Interactor->Render ();
00414     return;
00415   }
00416 
00417   std::string key (Interactor->GetKeySym ());
00418   if (key.find ("XF86ZoomIn") != std::string::npos)
00419     zoomIn ();
00420   else if (key.find ("XF86ZoomOut") != std::string::npos)
00421     zoomOut ();
00422 
00423   switch (Interactor->GetKeyCode ())
00424   {
00425     case 'h': case 'H':
00426     {
00427       pcl::console::print_info ("| Help:\n"
00428                   "-------\n"
00429                   "          p, P   : switch to a point-based representation\n"
00430                   "          w, W   : switch to a wireframe-based representation (where available)\n"
00431                   "          s, S   : switch to a surface-based representation (where available)\n"
00432                   "\n"
00433                   "          j, J   : take a .PNG snapshot of the current window view\n"
00434                   "          c, C   : display current camera/window parameters\n"
00435                   "          f, F   : fly to point mode\n"
00436                   "\n"
00437                   "          e, E   : exit the interactor\n"
00438                   "          q, Q   : stop and call VTK's TerminateApp\n"
00439                   "\n"
00440                   "           +/-   : increment/decrement overall point size\n"
00441                   "     +/- [+ ALT] : zoom in/out \n"
00442                   "\n"
00443                   "          g, G   : display scale grid (on/off)\n"
00444                   "          u, U   : display lookup table (on/off)\n"
00445                   "\n"
00446                   "    r, R [+ ALT] : reset camera [to viewpoint = {0, 0, 0} -> center_{x, y, z}]\n"
00447                   "\n"
00448                   "    ALT + s, S   : turn stereo mode on/off\n"
00449                   "    ALT + f, F   : switch between maximized window mode and original size\n"
00450                   "\n"
00451                   "          l, L           : list all available geometric and color handlers for the current actor map\n"
00452                   "    ALT + 0..9 [+ CTRL]  : switch between different geometric handlers (where available)\n"
00453                   "          0..9 [+ CTRL]  : switch between different color handlers (where available)\n"
00454                   "\n"
00455                   "    SHIFT + left click   : select a point\n"
00456                   "\n"
00457                   "          x, X   : toggle rubber band selection mode for left mouse button\n"
00458           );
00459       break;
00460     }
00461 
00462     // Get the list of available handlers
00463     case 'l': case 'L':
00464     {
00465       // Iterate over the entire actors list and extract the geomotry/color handlers list
00466       for (CloudActorMap::iterator it = actors_->begin (); it != actors_->end (); ++it)
00467       {
00468         std::list<std::string> geometry_handlers_list, color_handlers_list;
00469         CloudActor *act = &(*it).second;
00470         for (size_t i = 0; i < act->geometry_handlers.size (); ++i)
00471           geometry_handlers_list.push_back (act->geometry_handlers[i]->getFieldName ());
00472         for (size_t i = 0; i < act->color_handlers.size (); ++i)
00473           color_handlers_list.push_back (act->color_handlers[i]->getFieldName ());
00474 
00475         if (!geometry_handlers_list.empty ())
00476         {
00477           int i = 0;
00478           pcl::console::print_info ("List of available geometry handlers for actor "); pcl::console::print_value ("%s: ", (*it).first.c_str ());
00479           for (std::list<std::string>::iterator git = geometry_handlers_list.begin (); git != geometry_handlers_list.end (); ++git)
00480             pcl::console::print_value ("%s(%d) ", (*git).c_str (), ++i);
00481           pcl::console::print_info ("\n");
00482         }
00483         if (!color_handlers_list.empty ())
00484         {
00485           int i = 0;
00486           pcl::console::print_info ("List of available color handlers for actor "); pcl::console::print_value ("%s: ", (*it).first.c_str ());
00487           for (std::list<std::string>::iterator cit = color_handlers_list.begin (); cit != color_handlers_list.end (); ++cit)
00488             pcl::console::print_value ("%s(%d) ", (*cit).c_str (), ++i);
00489           pcl::console::print_info ("\n");
00490         }
00491       }
00492 
00493       break;
00494     }
00495 
00496     // Switch representation to points
00497     case 'p': case 'P':
00498     {
00499       vtkSmartPointer<vtkActorCollection> ac = CurrentRenderer->GetActors ();
00500       vtkCollectionSimpleIterator ait;
00501       for (ac->InitTraversal (ait); vtkActor* actor = ac->GetNextActor (ait); )
00502       {
00503         for (actor->InitPathTraversal (); vtkAssemblyPath* path = actor->GetNextPath (); )
00504         {
00505           vtkSmartPointer<vtkActor> apart = reinterpret_cast <vtkActor*> (path->GetLastNode ()->GetViewProp ());
00506           apart->GetProperty ()->SetRepresentationToPoints ();
00507         }
00508       }
00509       break;
00510     }
00511     // Save a PNG snapshot with the current screen
00512     case 'j': case 'J':
00513     {
00514       char cam_fn[80], snapshot_fn[80];
00515       unsigned t = static_cast<unsigned> (time (0));
00516       sprintf (snapshot_fn, "screenshot-%d.png" , t);
00517       saveScreenshot (snapshot_fn);
00518 
00519       sprintf (cam_fn, "screenshot-%d.cam", t);
00520       ofstream ofs_cam;
00521       ofs_cam.open (cam_fn);
00522       vtkSmartPointer<vtkCamera> cam = Interactor->GetRenderWindow ()->GetRenderers ()->GetFirstRenderer ()->GetActiveCamera ();
00523       double clip[2], focal[3], pos[3], view[3];
00524       cam->GetClippingRange (clip);
00525       cam->GetFocalPoint (focal);
00526       cam->GetPosition (pos);
00527       cam->GetViewUp (view);
00528       int *win_pos = Interactor->GetRenderWindow ()->GetPosition ();
00529       int *win_size = Interactor->GetRenderWindow ()->GetSize ();
00530       ofs_cam << clip[0]  << "," << clip[1]  << "/" << focal[0] << "," << focal[1] << "," << focal[2] << "/" <<
00531                  pos[0]   << "," << pos[1]   << "," << pos[2]   << "/" << view[0]  << "," << view[1]  << "," << view[2] << "/" <<
00532                  cam->GetViewAngle () / 180.0 * M_PI  << "/" << win_size[0] << "," << win_size[1] << "/" << win_pos[0] << "," << win_pos[1]
00533               << endl;
00534       ofs_cam.close ();
00535 
00536       pcl::console::print_info ("Screenshot (%s) and camera information (%s) successfully captured.\n", snapshot_fn, cam_fn);
00537       break;
00538     }
00539     // display current camera settings/parameters
00540     case 'c': case 'C':
00541     {
00542       vtkSmartPointer<vtkCamera> cam = Interactor->GetRenderWindow ()->GetRenderers ()->GetFirstRenderer ()->GetActiveCamera ();
00543       double clip[2], focal[3], pos[3], view[3];
00544       cam->GetClippingRange (clip);
00545       cam->GetFocalPoint (focal);
00546       cam->GetPosition (pos);
00547       cam->GetViewUp (view);
00548       int *win_pos = Interactor->GetRenderWindow ()->GetPosition ();
00549       int *win_size = Interactor->GetRenderWindow ()->GetSize ();
00550       std::cerr << clip[0]  << "," << clip[1]  << "/" << focal[0] << "," << focal[1] << "," << focal[2] << "/" <<
00551                    pos[0]   << "," << pos[1]   << "," << pos[2]   << "/" << view[0]  << "," << view[1]  << "," << view[2] << "/" <<
00552                    cam->GetViewAngle () / 180.0 * M_PI  << "/" << win_size[0] << "," << win_size[1] << "/" << win_pos[0] << "," << win_pos[1]
00553                 << endl;
00554       break;
00555     }
00556     case '=':
00557     {
00558       zoomIn();
00559       break;
00560     }
00561     case 43:        // KEY_PLUS
00562     {
00563       if(alt)
00564         zoomIn ();
00565       else
00566       {
00567         vtkSmartPointer<vtkActorCollection> ac = CurrentRenderer->GetActors ();
00568         vtkCollectionSimpleIterator ait;
00569         for (ac->InitTraversal (ait); vtkActor* actor = ac->GetNextActor (ait); )
00570         {
00571           for (actor->InitPathTraversal (); vtkAssemblyPath* path = actor->GetNextPath (); )
00572           {
00573             vtkSmartPointer<vtkActor> apart = reinterpret_cast <vtkActor*> (path->GetLastNode ()->GetViewProp ());
00574             float psize = apart->GetProperty ()->GetPointSize ();
00575             if (psize < 63.0f)
00576               apart->GetProperty ()->SetPointSize (psize + 1.0f);
00577           }
00578         }
00579       }
00580       break;
00581     }
00582     case 45:        // KEY_MINUS
00583     {
00584       if(alt)
00585         zoomOut ();
00586       else
00587       {
00588         vtkSmartPointer<vtkActorCollection> ac = CurrentRenderer->GetActors ();
00589         vtkCollectionSimpleIterator ait;
00590         for (ac->InitTraversal (ait); vtkActor* actor = ac->GetNextActor (ait); )
00591         {
00592           for (actor->InitPathTraversal (); vtkAssemblyPath* path = actor->GetNextPath (); )
00593           {
00594             vtkSmartPointer<vtkActor> apart = static_cast<vtkActor*> (path->GetLastNode ()->GetViewProp ());
00595             float psize = apart->GetProperty ()->GetPointSize ();
00596             if (psize > 1.0f)
00597               apart->GetProperty ()->SetPointSize (psize - 1.0f);
00598           }
00599         }
00600       }
00601       break;
00602     }
00603     // Switch between maximize and original window size
00604     case 'f': case 'F':
00605     {
00606       if (keymod)
00607       {
00608         // Get screen size
00609         int *temp = Interactor->GetRenderWindow ()->GetScreenSize ();
00610         int scr_size[2]; scr_size[0] = temp[0]; scr_size[1] = temp[1];
00611 
00612         // Get window size
00613         temp = Interactor->GetRenderWindow ()->GetSize ();
00614         int win_size[2]; win_size[0] = temp[0]; win_size[1] = temp[1];
00615         // Is window size = max?
00616         if (win_size[0] == max_win_height_ && win_size[1] == max_win_width_)
00617         {
00618           // Set the previously saved 'current' window size
00619           Interactor->GetRenderWindow ()->SetSize (win_height_, win_width_);
00620           // Set the previously saved window position
00621           Interactor->GetRenderWindow ()->SetPosition (win_pos_x_, win_pos_y_);
00622           Interactor->GetRenderWindow ()->Render ();
00623           Interactor->Render ();
00624         }
00625         // Set to max
00626         else
00627         {
00628           int *win_pos = Interactor->GetRenderWindow ()->GetPosition ();
00629           // Save the current window position
00630           win_pos_x_  = win_pos[0];
00631           win_pos_y_  = win_pos[1];
00632           // Save the current window size
00633           win_height_ = win_size[0];
00634           win_width_  = win_size[1];
00635           // Set the maximum window size
00636           Interactor->GetRenderWindow ()->SetSize (scr_size[0], scr_size[1]);
00637           Interactor->GetRenderWindow ()->Render ();
00638           Interactor->Render ();
00639           int *win_size = Interactor->GetRenderWindow ()->GetSize ();
00640           // Save the maximum window size
00641           max_win_height_ = win_size[0];
00642           max_win_width_  = win_size[1];
00643         }
00644       }
00645       else
00646       {
00647         AnimState = VTKIS_ANIM_ON;
00648         vtkAssemblyPath *path = NULL;
00649         Interactor->GetPicker ()->Pick (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1], 0.0, CurrentRenderer);
00650         vtkAbstractPropPicker *picker;
00651         if ((picker = vtkAbstractPropPicker::SafeDownCast (Interactor->GetPicker ())))
00652           path = picker->GetPath ();
00653         if (path != NULL)
00654           Interactor->FlyTo (CurrentRenderer, picker->GetPickPosition ());
00655         AnimState = VTKIS_ANIM_OFF;
00656       }
00657       break;
00658     }
00659     // 's'/'S' w/out ALT
00660     case 's': case 'S':
00661     {
00662       if (keymod)
00663       {
00664         int stereo_render = Interactor->GetRenderWindow ()->GetStereoRender ();
00665         if (!stereo_render)
00666         {
00667           if (stereo_anaglyph_mask_default_)
00668           {
00669             Interactor->GetRenderWindow ()->SetAnaglyphColorMask (4, 3);
00670             stereo_anaglyph_mask_default_ = false;
00671           }
00672           else
00673           {
00674             Interactor->GetRenderWindow ()->SetAnaglyphColorMask (2, 5);
00675             stereo_anaglyph_mask_default_ = true;
00676           }
00677         }
00678         Interactor->GetRenderWindow ()->SetStereoRender (!stereo_render);
00679         Interactor->GetRenderWindow ()->Render ();
00680         Interactor->Render ();
00681       }
00682       else
00683         Superclass::OnKeyDown ();
00684       break;
00685     }
00686 
00687     // Display a grid/scale over the screen
00688     case 'g': case 'G':
00689     {
00690       if (!grid_enabled_)
00691       {
00692         grid_actor_->TopAxisVisibilityOn ();
00693         CurrentRenderer->AddViewProp (grid_actor_);
00694         grid_enabled_ = true;
00695       }
00696       else
00697       {
00698         CurrentRenderer->RemoveViewProp (grid_actor_);
00699         grid_enabled_ = false;
00700       }
00701       break;
00702     }
00703 
00704     case 'o': case 'O':
00705     {
00706       vtkSmartPointer<vtkCamera> cam = CurrentRenderer->GetActiveCamera ();
00707       int flag = cam->GetParallelProjection ();
00708       cam->SetParallelProjection (!flag);
00709 
00710       CurrentRenderer->SetActiveCamera (cam);
00711       CurrentRenderer->Render ();
00712       break;
00713     }
00714     // Display a LUT actor on screen
00715     case 'u': case 'U':
00716     {
00717       CloudActorMap::iterator it;
00718       for (it = actors_->begin (); it != actors_->end (); ++it)
00719       {
00720         CloudActor *act = &(*it).second;
00721 
00722         vtkScalarsToColors* lut = act->actor->GetMapper ()->GetLookupTable ();
00723         lut_actor_->SetLookupTable (lut);
00724         lut_actor_->Modified ();
00725       }
00726       if (!lut_enabled_)
00727       {
00728         CurrentRenderer->AddActor (lut_actor_);
00729         lut_actor_->SetVisibility (true);
00730         lut_enabled_ = true;
00731       }
00732       else
00733       {
00734         CurrentRenderer->RemoveActor (lut_actor_);
00735         lut_enabled_ = false;
00736       }
00737       CurrentRenderer->Render ();
00738       break;
00739     }
00740 
00741     // Overwrite the camera reset
00742     case 'r': case 'R':
00743     {
00744       if (!keymod)
00745       {
00746         FindPokedRenderer(Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00747         if(CurrentRenderer != 0)
00748           CurrentRenderer->ResetCamera ();
00749         else
00750           PCL_WARN ("no current renderer on the interactor style.");
00751 
00752         CurrentRenderer->Render ();
00753         break;
00754       }
00755 
00756       vtkSmartPointer<vtkCamera> cam = CurrentRenderer->GetActiveCamera ();
00757       
00758       static CloudActorMap::iterator it = actors_->begin ();
00759       // it might be that some actors don't have a valid transformation set -> we skip them to avoid a seg fault.
00760       bool found_transformation = false;
00761       for (unsigned idx = 0; idx < actors_->size (); ++idx, ++it)
00762       {
00763         if (it == actors_->end ())
00764           it = actors_->begin ();
00765         
00766         const CloudActor& actor = it->second;
00767         if (actor.viewpoint_transformation_.GetPointer ())
00768         {
00769           found_transformation = true;
00770           break;
00771         }
00772       }
00773       
00774       // if a valid transformation was found, use it otherwise fall back to default view point.
00775       if (found_transformation)
00776       {
00777         const CloudActor& actor = it->second;
00778         cam->SetPosition (actor.viewpoint_transformation_->GetElement (0, 3),
00779                           actor.viewpoint_transformation_->GetElement (1, 3),
00780                           actor.viewpoint_transformation_->GetElement (2, 3));
00781 
00782         cam->SetFocalPoint (actor.viewpoint_transformation_->GetElement (0, 3) - actor.viewpoint_transformation_->GetElement (0, 2),
00783                             actor.viewpoint_transformation_->GetElement (1, 3) - actor.viewpoint_transformation_->GetElement (1, 2),
00784                             actor.viewpoint_transformation_->GetElement (2, 3) - actor.viewpoint_transformation_->GetElement (2, 2));
00785 
00786         cam->SetViewUp (actor.viewpoint_transformation_->GetElement (0, 1),
00787                         actor.viewpoint_transformation_->GetElement (1, 1),
00788                         actor.viewpoint_transformation_->GetElement (2, 1));
00789       }
00790       else
00791       {
00792         cam->SetPosition (0, 0, 0);
00793         cam->SetFocalPoint (0, 0, 1);
00794         cam->SetViewUp (0, -1, 0);
00795       }
00796 
00797       // go to the next actor for the next key-press event.
00798       if (it != actors_->end ())
00799         ++it;
00800       else
00801         it = actors_->begin ();
00802       
00803       CurrentRenderer->SetActiveCamera (cam);
00804       CurrentRenderer->ResetCameraClippingRange ();
00805       CurrentRenderer->Render ();
00806       break;
00807     }
00808 
00809     case 'x' : case 'X' :
00810     {
00811       CurrentMode = (CurrentMode == ORIENT_MODE) ? SELECT_MODE : ORIENT_MODE;
00812       if (CurrentMode == SELECT_MODE)
00813       {
00814         // Save the point picker
00815         point_picker_ = static_cast<vtkPointPicker*> (Interactor->GetPicker ());
00816         // Switch for an area picker
00817         vtkSmartPointer<vtkAreaPicker> area_picker = vtkSmartPointer<vtkAreaPicker>::New ();
00818         Interactor->SetPicker (area_picker);
00819       }
00820       else
00821       {
00822         // Restore point picker
00823         Interactor->SetPicker (point_picker_);
00824       }
00825       break;
00826     }
00827 
00828     case 'q': case 'Q':
00829     {
00830       Interactor->ExitCallback ();
00831       return;
00832     }
00833     default:
00834     {
00835       Superclass::OnKeyDown ();
00836       break;
00837     }
00838   }
00839 
00840   KeyboardEvent event (true, Interactor->GetKeySym (), Interactor->GetKeyCode (), Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00841   keyboard_signal_ (event);
00842 
00843   rens_->Render ();
00844   Interactor->Render ();
00845 }
00846 
00848 void
00849 pcl::visualization::PCLVisualizerInteractorStyle::OnKeyUp ()
00850 {
00851   KeyboardEvent event (false, Interactor->GetKeySym (), Interactor->GetKeyCode (), Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00852   keyboard_signal_ (event);
00853   Superclass::OnKeyUp ();
00854 }
00855 
00857 void
00858 pcl::visualization::PCLVisualizerInteractorStyle::OnMouseMove ()
00859 {
00860   int x = this->Interactor->GetEventPosition()[0];
00861   int y = this->Interactor->GetEventPosition()[1];
00862   MouseEvent event (MouseEvent::MouseMove, MouseEvent::NoButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00863   mouse_signal_ (event);
00864   Superclass::OnMouseMove ();
00865 }
00866 
00868 void
00869 pcl::visualization::PCLVisualizerInteractorStyle::OnLeftButtonDown ()
00870 {
00871 
00872   int x = this->Interactor->GetEventPosition()[0];
00873   int y = this->Interactor->GetEventPosition()[1];
00874 
00875   if (Interactor->GetRepeatCount () == 0)
00876   {
00877     MouseEvent event (MouseEvent::MouseButtonPress, MouseEvent::LeftButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00878     mouse_signal_ (event);
00879   }
00880   else
00881   {
00882     MouseEvent event (MouseEvent::MouseDblClick, MouseEvent::LeftButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00883     mouse_signal_ (event);
00884   }
00885   Superclass::OnLeftButtonDown ();
00886 }
00887 
00889 void
00890 pcl::visualization::PCLVisualizerInteractorStyle::OnLeftButtonUp ()
00891 {
00892   int x = this->Interactor->GetEventPosition()[0];
00893   int y = this->Interactor->GetEventPosition()[1];
00894   MouseEvent event (MouseEvent::MouseButtonRelease, MouseEvent::LeftButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00895   mouse_signal_ (event);
00896   Superclass::OnLeftButtonUp ();
00897 }
00898 
00900 void
00901 pcl::visualization::PCLVisualizerInteractorStyle::OnMiddleButtonDown ()
00902 {
00903   int x = this->Interactor->GetEventPosition()[0];
00904   int y = this->Interactor->GetEventPosition()[1];
00905   if (Interactor->GetRepeatCount () == 0)
00906   {
00907     MouseEvent event (MouseEvent::MouseButtonPress, MouseEvent::MiddleButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00908     mouse_signal_ (event);
00909   }
00910   else
00911   {
00912     MouseEvent event (MouseEvent::MouseDblClick, MouseEvent::MiddleButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00913     mouse_signal_ (event);
00914   }
00915   Superclass::OnMiddleButtonDown ();
00916 }
00917 
00919 void
00920 pcl::visualization::PCLVisualizerInteractorStyle::OnMiddleButtonUp ()
00921 {
00922   int x = this->Interactor->GetEventPosition()[0];
00923   int y = this->Interactor->GetEventPosition()[1];
00924   MouseEvent event (MouseEvent::MouseButtonRelease, MouseEvent::MiddleButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00925   mouse_signal_ (event);
00926   Superclass::OnMiddleButtonUp ();
00927 }
00928 
00930 void
00931 pcl::visualization::PCLVisualizerInteractorStyle::OnRightButtonDown ()
00932 {
00933   int x = this->Interactor->GetEventPosition()[0];
00934   int y = this->Interactor->GetEventPosition()[1];
00935   if (Interactor->GetRepeatCount () == 0)
00936   {
00937     MouseEvent event (MouseEvent::MouseButtonPress, MouseEvent::RightButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00938     mouse_signal_ (event);
00939   }
00940   else
00941   {
00942     MouseEvent event (MouseEvent::MouseDblClick, MouseEvent::RightButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00943     mouse_signal_ (event);
00944   }
00945   Superclass::OnRightButtonDown ();
00946 }
00947 
00949 void
00950 pcl::visualization::PCLVisualizerInteractorStyle::OnRightButtonUp ()
00951 {
00952   int x = this->Interactor->GetEventPosition()[0];
00953   int y = this->Interactor->GetEventPosition()[1];
00954   MouseEvent event (MouseEvent::MouseButtonRelease, MouseEvent::RightButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00955   mouse_signal_ (event);
00956   Superclass::OnRightButtonUp ();
00957 }
00958 
00960 void
00961 pcl::visualization::PCLVisualizerInteractorStyle::OnMouseWheelForward ()
00962 {
00963   int x = this->Interactor->GetEventPosition()[0];
00964   int y = this->Interactor->GetEventPosition()[1];
00965   MouseEvent event (MouseEvent::MouseScrollUp, MouseEvent::VScroll, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00966   mouse_signal_ (event);
00967   if (Interactor->GetRepeatCount ())
00968     mouse_signal_ (event);
00969   
00970   if (Interactor->GetAltKey ())
00971   {
00972     // zoom
00973     vtkSmartPointer<vtkCamera> cam = CurrentRenderer->GetActiveCamera ();
00974     double opening_angle = cam->GetViewAngle ();
00975     if (opening_angle > 15.0)
00976       opening_angle -= 1.0;
00977     
00978     cam->SetViewAngle (opening_angle);
00979     cam->Modified ();
00980     CurrentRenderer->SetActiveCamera (cam);
00981     CurrentRenderer->ResetCameraClippingRange ();
00982     CurrentRenderer->Modified ();    
00983     CurrentRenderer->Render ();
00984     rens_->Render ();
00985     Interactor->Render ();
00986   }
00987   else
00988   Superclass::OnMouseWheelForward ();
00989 }
00990 
00992 void
00993 pcl::visualization::PCLVisualizerInteractorStyle::OnMouseWheelBackward ()
00994 {
00995   int x = this->Interactor->GetEventPosition()[0];
00996   int y = this->Interactor->GetEventPosition()[1];
00997   MouseEvent event (MouseEvent::MouseScrollDown, MouseEvent::VScroll, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey (), Superclass::CurrentMode);
00998   mouse_signal_ (event);
00999   if (Interactor->GetRepeatCount ())
01000     mouse_signal_ (event);
01001   
01002   if (Interactor->GetAltKey ())
01003   {
01004     // zoom
01005     vtkSmartPointer<vtkCamera> cam = CurrentRenderer->GetActiveCamera ();
01006     double opening_angle = cam->GetViewAngle ();
01007     if (opening_angle < 170.0)
01008       opening_angle += 1.0;
01009     
01010     cam->SetViewAngle (opening_angle);
01011     cam->Modified ();
01012     CurrentRenderer->SetActiveCamera (cam);
01013     CurrentRenderer->ResetCameraClippingRange ();
01014     CurrentRenderer->Modified ();
01015     CurrentRenderer->Render ();
01016     rens_->Render ();
01017     Interactor->Render ();
01018   }
01019   else
01020     Superclass::OnMouseWheelBackward ();
01021 }
01022 
01024 void
01025 pcl::visualization::PCLVisualizerInteractorStyle::OnTimer ()
01026 {
01027   if (!init_)
01028   {
01029     pcl::console::print_error ("[PCLVisualizerInteractorStyle] Interactor style not initialized. Please call Initialize () before continuing.\n");
01030     return;
01031   }
01032 
01033   if (!rens_)
01034   {
01035     pcl::console::print_error ("[PCLVisualizerInteractorStyle] No renderer collection given! Use SetRendererCollection () before continuing.\n");
01036     return;
01037   }
01038   rens_->Render ();
01039   Interactor->Render ();
01040 }
01041 
01044 void
01045 pcl::visualization::PCLHistogramVisualizerInteractorStyle::Initialize ()
01046 {
01047   init_ = true;
01048 }
01049 
01051 void
01052 pcl::visualization::PCLHistogramVisualizerInteractorStyle::OnKeyDown ()
01053 {
01054   if (!init_)
01055   {
01056     pcl::console::print_error ("[PCLHistogramVisualizerInteractorStyle] Interactor style not initialized. Please call Initialize () before continuing.\n");
01057     return;
01058   }
01059 
01060   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
01061 
01062   //fprintf (stderr, "Key sym: %s\n", Interactor->GetKeySym ());
01063   // ---[ Check the rest of the key codes
01064   switch (Interactor->GetKeyCode ())
01065   {
01066     case 'q': case 'Q':
01067     {
01068       Interactor->ExitCallback ();
01069       return;
01070     }
01071     // Switch representation to wireframe
01072     default:
01073     {
01074       Superclass::OnKeyDown ();
01075     }
01076   }
01077   Interactor->Render ();
01078 }
01079 
01081 void
01082 pcl::visualization::PCLHistogramVisualizerInteractorStyle::OnTimer ()
01083 {
01084   if (!init_)
01085   {
01086     pcl::console::print_error ("[PCLHistogramVisualizerInteractorStyle] Interactor style not initialized. Please call Initialize () before continuing.\n");
01087     return;
01088   }
01089 
01090   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
01091     (*am_it).second.ren_->Render ();
01092 }
01093 
01094 namespace pcl
01095 {
01096   namespace visualization
01097   {
01098     // Standard VTK macro for *New ()
01099     vtkStandardNewMacro (PCLVisualizerInteractorStyle);
01100     vtkStandardNewMacro (PCLHistogramVisualizerInteractorStyle);
01101   }
01102 }
01103 


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