interactor_style.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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 Willow Garage, Inc. 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  * $Id: interactor_style.cpp 4360 2012-02-10 01:01:11Z rusu $
00035  *
00036  */
00037 
00038 #include <list>
00039 #include <pcl/visualization/common/io.h>
00040 #include <pcl/visualization/interactor_style.h>
00041 #include <vtkPolyData.h>
00042 #include <vtkMapper.h>
00043 #include <vtkPolyDataMapper.h>
00044 #include <vtkPointData.h>
00045 #include <vtkCellArray.h>
00046 #include <vtkAppendPolyData.h>
00047 #include <vtkTextProperty.h>
00048 #include <vtkAbstractPicker.h>
00049 #include <vtkAbstractPropPicker.h>
00050 #include <vtkPlanes.h>
00051 #include <vtkPointPicker.h>
00052 #include <vtkMatrix4x4.h>
00053 
00055 void
00056 pcl::visualization::PCLVisualizerInteractorStyle::Initialize ()
00057 {
00058   modifier_ = pcl::visualization::INTERACTOR_KB_MOD_ALT;
00059   // Set windows size (width, height) to unknown (-1)
00060   win_height_ = win_width_ = -1;
00061   win_pos_x_ = win_pos_y_ = 0;
00062   max_win_height_ = max_win_width_ = -1;
00063 
00064   // Grid is disabled by default
00065   grid_enabled_ = false;
00066   grid_actor_ = vtkSmartPointer<vtkLegendScaleActor>::New ();
00067 
00068   // LUT is disabled by default
00069   lut_enabled_ = false;
00070   lut_actor_ = vtkSmartPointer<vtkScalarBarActor>::New ();
00071   lut_actor_->SetTitle ("");
00072   lut_actor_->SetOrientationToHorizontal ();
00073   lut_actor_->SetPosition (0.05, 0.01);
00074   lut_actor_->SetWidth (0.9);
00075   lut_actor_->SetHeight (0.1);
00076   lut_actor_->SetNumberOfLabels (lut_actor_->GetNumberOfLabels () * 2);
00077   vtkSmartPointer<vtkTextProperty> prop = lut_actor_->GetLabelTextProperty ();
00078   prop->SetFontSize (10);
00079   lut_actor_->SetLabelTextProperty (prop);
00080   lut_actor_->SetTitleTextProperty (prop);
00081 
00082   // Create the image filter and PNG writer objects
00083   wif_ = vtkSmartPointer<vtkWindowToImageFilter>::New ();
00084   snapshot_writer_ = vtkSmartPointer<vtkPNGWriter>::New ();
00085   snapshot_writer_->SetInputConnection (wif_->GetOutputPort ());
00086 
00087   init_ = true;
00088 
00089   stereo_anaglyph_mask_default_ = true;
00090 
00091   // Add our own mouse callback before any user callback. Used for accurate point picking.
00092   mouse_callback_ = vtkSmartPointer<pcl::visualization::PointPickingCallback>::New ();
00093   AddObserver (vtkCommand::LeftButtonPressEvent, mouse_callback_);
00094 }
00095 
00097 void
00098 pcl::visualization::PCLVisualizerInteractorStyle::saveScreenshot (const std::string &file)
00099 {
00100   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00101   wif_->SetInput (Interactor->GetRenderWindow ());
00102   wif_->Modified ();      // Update the WindowToImageFilter
00103   snapshot_writer_->Modified ();
00104   snapshot_writer_->SetFileName (file.c_str ());
00105   snapshot_writer_->Write ();
00106 }
00107 
00109 void
00110 pcl::visualization::PCLVisualizerInteractorStyle::zoomIn ()
00111 {
00112   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00113   // Zoom in
00114   StartDolly ();
00115   double factor = 10.0 * 0.2 * .5;
00116   Dolly (pow (1.1, factor));
00117   EndDolly ();
00118 }
00119 
00121 void
00122 pcl::visualization::PCLVisualizerInteractorStyle::zoomOut ()
00123 {
00124   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00125   // Zoom out
00126   StartDolly ();
00127   double factor = 10.0 * -0.2 * .5;
00128   Dolly (pow (1.1, factor));
00129   EndDolly ();
00130 }
00131 
00133 void
00134 pcl::visualization::PCLVisualizerInteractorStyle::OnChar ()
00135 {
00136   // Make sure we ignore the same events we handle in OnKeyDown to avoid calling things twice
00137   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00138   if (Interactor->GetKeyCode () >= '0' && Interactor->GetKeyCode () <= '9')
00139     return;
00140   std::string key (Interactor->GetKeySym ());
00141   if (key.find ("XF86ZoomIn") != std::string::npos)
00142     zoomIn ();
00143   else if (key.find ("XF86ZoomOut") != std::string::npos)
00144     zoomOut ();
00145 
00146   bool keymod = false;
00147   switch (modifier_)
00148   {
00149     case INTERACTOR_KB_MOD_ALT:
00150     {
00151       keymod = Interactor->GetAltKey ();
00152       break;
00153     }
00154     case INTERACTOR_KB_MOD_CTRL:
00155     {
00156       keymod = Interactor->GetControlKey ();
00157       break;
00158     }
00159     case INTERACTOR_KB_MOD_SHIFT:
00160     {
00161       keymod = Interactor->GetShiftKey ();
00162       break;
00163     }
00164   }
00165 
00166   switch (Interactor->GetKeyCode ())
00167   {
00168     // All of the options below simply exit
00169     case 'h': case 'H':
00170     case 'l': case 'L':
00171     case 'p': case 'P':
00172     case 'j': case 'J':
00173     case 'c': case 'C':
00174     case 43:        // KEY_PLUS
00175     case 45:        // KEY_MINUS
00176     case 'f': case 'F':
00177     case 'g': case 'G':
00178     case 'o': case 'O':
00179     case 'u': case 'U':
00180     case 'q': case 'Q':
00181     {
00182       break;
00183     }
00184     // S and R have a special !ALT case
00185     case 'r': case 'R':
00186     case 's': case 'S':
00187     {
00188       if (!keymod)
00189         Superclass::OnChar ();
00190       break;
00191     }
00192     default:
00193     {
00194       Superclass::OnChar ();
00195       break;
00196     }
00197   }
00198 }
00199 
00201 boost::signals2::connection
00202 pcl::visualization::PCLVisualizerInteractorStyle::registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> callback)
00203 {
00204   return (mouse_signal_.connect (callback));
00205 }
00206 
00208 boost::signals2::connection
00209 pcl::visualization::PCLVisualizerInteractorStyle::registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> callback)
00210 {
00211   return (keyboard_signal_.connect (callback));
00212 }
00213 
00215 boost::signals2::connection
00216 pcl::visualization::PCLVisualizerInteractorStyle::registerPointPickingCallback (boost::function<void (const pcl::visualization::PointPickingEvent&)> callback)
00217 {
00218   return (point_picking_signal_.connect (callback));
00219 }
00220 
00222 void
00223 pcl::visualization::PCLVisualizerInteractorStyle::OnKeyDown ()
00224 {
00225   if (!init_)
00226   {
00227     pcl::console::print_error ("[PCLVisualizerInteractorStyle] Interactor style not initialized. Please call Initialize () before continuing.\n");
00228     return;
00229   }
00230 
00231   if (!rens_)
00232   {
00233     pcl::console::print_error ("[PCLVisualizerInteractorStyle] No renderer collection given! Use SetRendererCollection () before continuing.\n");
00234     return;
00235   }
00236 
00237   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00238 
00239   if (wif_->GetInput () == NULL)
00240   {
00241     wif_->SetInput (Interactor->GetRenderWindow ());
00242     wif_->Modified ();
00243     snapshot_writer_->Modified ();
00244   }
00245 
00246   // Save the initial windows width/height
00247   if (win_height_ == -1 || win_width_ == -1)
00248   {
00249     int *win_size = Interactor->GetRenderWindow ()->GetSize ();
00250     win_height_ = win_size[0];
00251     win_width_  = win_size[1];
00252   }
00253 
00254   // Get the status of special keys (Cltr+Alt+Shift)
00255   bool shift = Interactor->GetShiftKey   ();
00256   bool ctrl  = Interactor->GetControlKey ();
00257   bool alt   = Interactor->GetAltKey ();
00258 
00259   bool keymod = false;
00260   switch (modifier_)
00261   {
00262     case INTERACTOR_KB_MOD_ALT:
00263     {
00264       keymod = alt;
00265       break;
00266     }
00267     case INTERACTOR_KB_MOD_CTRL:
00268     {
00269       keymod = ctrl;
00270       break;
00271     }
00272     case INTERACTOR_KB_MOD_SHIFT:
00273     {
00274       keymod = shift;
00275       break;
00276     }
00277   }
00278 
00279   // ---[ Check the rest of the key codes
00280 
00281   // Switch between point color/geometry handlers
00282   if (Interactor->GetKeySym () && Interactor->GetKeySym ()[0]  >= '0' && Interactor->GetKeySym ()[0] <= '9')
00283   {
00284     CloudActorMap::iterator it;
00285     int index = Interactor->GetKeySym ()[0] - '0' - 1;
00286     if (index == -1) index = 9;
00287 
00288     // Add 10 more for CTRL+0..9 keys
00289     if (ctrl)
00290       index += 10;
00291 
00292     // Geometry ?
00293     if (keymod)
00294     {
00295       for (it = actors_->begin (); it != actors_->end (); ++it)
00296       {
00297         CloudActor *act = &(*it).second;
00298         if (index >= (int)act->geometry_handlers.size ())
00299           continue;
00300 
00301         // Save the geometry handler index for later usage
00302         act->geometry_handler_index_ = index;
00303 
00304         // Create the new geometry
00305         PointCloudGeometryHandler<sensor_msgs::PointCloud2>::ConstPtr geometry_handler = act->geometry_handlers[index];
00306 
00307         // Use the handler to obtain the geometry
00308         vtkSmartPointer<vtkPoints> points;
00309         geometry_handler->getGeometry (points);
00310 
00311         // Set the vertices
00312         vtkSmartPointer<vtkCellArray> vertices = vtkSmartPointer<vtkCellArray>::New ();
00313         for (vtkIdType i = 0; i < (int)points->GetNumberOfPoints (); ++i)
00314           vertices->InsertNextCell ((vtkIdType)1, &i);
00315 
00316         // Create the data
00317         vtkSmartPointer<vtkPolyData> data = vtkSmartPointer<vtkPolyData>::New ();
00318         data->SetPoints (points);
00319         data->SetVerts (vertices);
00320         // Modify the mapper
00321         vtkPolyDataMapper* mapper = static_cast<vtkPolyDataMapper*>(act->actor->GetMapper ());
00322         mapper->SetInput (data);
00323         // Modify the actor
00324         act->actor->SetMapper (mapper);
00325         act->actor->Modified ();
00326       }
00327     }
00328     else
00329     {
00330       for (it = actors_->begin (); it != actors_->end (); ++it)
00331       {
00332         CloudActor *act = &(*it).second;
00333         // Check for out of bounds
00334         if (index >= (int)act->color_handlers.size ())
00335           continue;
00336 
00337         // Save the color handler index for later usage
00338         act->color_handler_index_ = index;
00339 
00340         // Get the new color
00341         PointCloudColorHandler<sensor_msgs::PointCloud2>::ConstPtr color_handler = act->color_handlers[index];
00342 
00343         vtkSmartPointer<vtkDataArray> scalars;
00344         color_handler->getColor (scalars);
00345         double minmax[2];
00346         scalars->GetRange (minmax);
00347         // Update the data
00348         vtkPolyData *data = static_cast<vtkPolyData*>(act->actor->GetMapper ()->GetInput ());
00349         data->GetPointData ()->SetScalars (scalars);
00350         data->Update ();
00351         // Modify the mapper
00352         vtkPolyDataMapper* mapper = static_cast<vtkPolyDataMapper*>(act->actor->GetMapper ());
00353         mapper->SetScalarRange (minmax);
00354         mapper->SetScalarModeToUsePointData ();
00355         mapper->SetInput (data);
00356         // Modify the actor
00357         act->actor->SetMapper (mapper);
00358         act->actor->Modified ();
00359       }
00360     }
00361 
00362     Interactor->Render ();
00363     return;
00364   }
00365 
00366   std::string key (Interactor->GetKeySym ());
00367   if (key.find ("XF86ZoomIn") != std::string::npos)
00368     zoomIn ();
00369   else if (key.find ("XF86ZoomOut") != std::string::npos)
00370     zoomOut ();
00371 
00372   switch (Interactor->GetKeyCode ())
00373   {
00374     case 'h': case 'H':
00375     {
00376       pcl::console::print_info ("| Help:\n"
00377                   "-------\n"
00378                   "          p, P   : switch to a point-based representation\n"
00379                   "          w, W   : switch to a wireframe-based representation (where available)\n"
00380                   "          s, S   : switch to a surface-based representation (where available)\n"
00381                   "\n"
00382                   "          j, J   : take a .PNG snapshot of the current window view\n"
00383                   "          c, C   : display current camera/window parameters\n"
00384                   "          f, F   : fly to point mode\n"
00385                   "\n"
00386                   "          e, E   : exit the interactor\n"
00387                   "          q, Q   : stop and call VTK's TerminateApp\n"
00388                   "\n"
00389                   "           +/-   : increment/decrement overall point size\n"
00390                   "     +/- [+ ALT] : zoom in/out \n"
00391                   "\n"
00392                   "          g, G   : display scale grid (on/off)\n"
00393                   "          u, U   : display lookup table (on/off)\n"
00394                   "\n"
00395                   "    r, R [+ ALT] : reset camera [to viewpoint = {0, 0, 0} -> center_{x, y, z}]\n"
00396                   "\n"
00397                   "    ALT + s, S   : turn stereo mode on/off\n"
00398                   "    ALT + f, F   : switch between maximized window mode and original size\n"
00399                   "\n"
00400                   "          l, L           : list all available geometric and color handlers for the current actor map\n"
00401                   "    ALT + 0..9 [+ CTRL]  : switch between different geometric handlers (where available)\n"
00402                   "          0..9 [+ CTRL]  : switch between different color handlers (where available)\n"
00403                   "\n"
00404                   "    SHIFT + left click   : select a point\n"
00405           );
00406       break;
00407     }
00408 
00409     // Get the list of available handlers
00410     case 'l': case 'L':
00411     {
00412       // Iterate over the entire actors list and extract the geomotry/color handlers list
00413       for (CloudActorMap::iterator it = actors_->begin (); it != actors_->end (); ++it)
00414       {
00415         std::list<std::string> geometry_handlers_list, color_handlers_list;
00416         CloudActor *act = &(*it).second;
00417         for (size_t i = 0; i < act->geometry_handlers.size (); ++i)
00418           geometry_handlers_list.push_back (act->geometry_handlers[i]->getFieldName ());
00419         for (size_t i = 0; i < act->color_handlers.size (); ++i)
00420           color_handlers_list.push_back (act->color_handlers[i]->getFieldName ());
00421 
00422         if (!geometry_handlers_list.empty ())
00423         {
00424           int i = 0;
00425           pcl::console::print_info ("List of available geometry handlers for actor "); pcl::console::print_value ("%s: ", (*it).first.c_str ());
00426           for (std::list<std::string>::iterator git = geometry_handlers_list.begin (); git != geometry_handlers_list.end (); ++git)
00427             pcl::console::print_value ("%s(%d) ", (*git).c_str (), ++i);
00428           pcl::console::print_info ("\n");
00429         }
00430         if (!color_handlers_list.empty ())
00431         {
00432           int i = 0;
00433           pcl::console::print_info ("List of available color handlers for actor "); pcl::console::print_value ("%s: ", (*it).first.c_str ());
00434           for (std::list<std::string>::iterator cit = color_handlers_list.begin (); cit != color_handlers_list.end (); ++cit)
00435             pcl::console::print_value ("%s(%d) ", (*cit).c_str (), ++i);
00436           pcl::console::print_info ("\n");
00437         }
00438       }
00439 
00440       break;
00441     }
00442 
00443     // Switch representation to points
00444     case 'p': case 'P':
00445     {
00446       vtkSmartPointer<vtkActorCollection> ac = CurrentRenderer->GetActors ();
00447       vtkCollectionSimpleIterator ait;
00448       for (ac->InitTraversal (ait); vtkActor* actor = ac->GetNextActor (ait); )
00449       {
00450         for (actor->InitPathTraversal (); vtkAssemblyPath* path = actor->GetNextPath (); )
00451         {
00452           vtkSmartPointer<vtkActor> apart = (vtkActor*)path->GetLastNode ()->GetViewProp ();
00453           apart->GetProperty ()->SetRepresentationToPoints ();
00454         }
00455       }
00456       break;
00457     }
00458     // Save a PNG snapshot with the current screen
00459     case 'j': case 'J':
00460     {
00461       char cam_fn[80], snapshot_fn[80];
00462       unsigned t = time (0);
00463       sprintf (snapshot_fn, "screenshot-%d.png" , t);
00464       saveScreenshot (snapshot_fn);
00465 
00466       sprintf (cam_fn, "screenshot-%d.cam", t);
00467       ofstream ofs_cam;
00468       ofs_cam.open (cam_fn);
00469       vtkSmartPointer<vtkCamera> cam = Interactor->GetRenderWindow ()->GetRenderers ()->GetFirstRenderer ()->GetActiveCamera ();
00470       double clip[2], focal[3], pos[3], view[3];
00471       cam->GetClippingRange (clip);
00472       cam->GetFocalPoint (focal);
00473       cam->GetPosition (pos);
00474       cam->GetViewUp (view);
00475       int *win_pos = Interactor->GetRenderWindow ()->GetPosition ();
00476       int *win_size = Interactor->GetRenderWindow ()->GetSize ();
00477       ofs_cam << clip[0]  << "," << clip[1]  << "/" << focal[0] << "," << focal[1] << "," << focal[2] << "/" <<
00478                  pos[0]   << "," << pos[1]   << "," << pos[2]   << "/" << view[0]  << "," << view[1]  << "," << view[2] << "/" <<
00479                  cam->GetViewAngle () / 180.0 * M_PI  << "/" << win_size[0] << "," << win_size[1] << "/" << win_pos[0] << "," << win_pos[1]
00480               << endl;
00481       ofs_cam.close ();
00482 
00483       pcl::console::print_info ("Screenshot (%s) and camera information (%s) successfully captured.\n", snapshot_fn, cam_fn);
00484       break;
00485     }
00486     // display current camera settings/parameters
00487     case 'c': case 'C':
00488     {
00489       vtkSmartPointer<vtkCamera> cam = Interactor->GetRenderWindow ()->GetRenderers ()->GetFirstRenderer ()->GetActiveCamera ();
00490       double clip[2], focal[3], pos[3], view[3];
00491       cam->GetClippingRange (clip);
00492       cam->GetFocalPoint (focal);
00493       cam->GetPosition (pos);
00494       cam->GetViewUp (view);
00495       int *win_pos = Interactor->GetRenderWindow ()->GetPosition ();
00496       int *win_size = Interactor->GetRenderWindow ()->GetSize ();
00497       std::cerr << clip[0]  << "," << clip[1]  << "/" << focal[0] << "," << focal[1] << "," << focal[2] << "/" <<
00498                    pos[0]   << "," << pos[1]   << "," << pos[2]   << "/" << view[0]  << "," << view[1]  << "," << view[2] << "/" <<
00499                    cam->GetViewAngle () / 180.0 * M_PI  << "/" << win_size[0] << "," << win_size[1] << "/" << win_pos[0] << "," << win_pos[1]
00500                 << endl;
00501       break;
00502     }
00503     case '=':
00504     {
00505       zoomIn();
00506       break;
00507     }
00508     case 43:        // KEY_PLUS
00509     {
00510       if(alt)
00511         zoomIn ();
00512       else
00513       {
00514         vtkSmartPointer<vtkActorCollection> ac = CurrentRenderer->GetActors ();
00515         vtkCollectionSimpleIterator ait;
00516         for (ac->InitTraversal (ait); vtkActor* actor = ac->GetNextActor (ait); )
00517         {
00518           for (actor->InitPathTraversal (); vtkAssemblyPath* path = actor->GetNextPath (); )
00519           {
00520             vtkSmartPointer<vtkActor> apart = (vtkActor*)path->GetLastNode ()->GetViewProp ();
00521             int psize = apart->GetProperty ()->GetPointSize ();
00522             if (psize < 63)
00523               apart->GetProperty ()->SetPointSize (psize + 1);
00524           }
00525         }
00526       }
00527       break;
00528     }
00529     case 45:        // KEY_MINUS
00530     {
00531       if(alt)
00532         zoomOut ();
00533       else
00534       {
00535         vtkSmartPointer<vtkActorCollection> ac = CurrentRenderer->GetActors ();
00536         vtkCollectionSimpleIterator ait;
00537         for (ac->InitTraversal (ait); vtkActor* actor = ac->GetNextActor (ait); )
00538         {
00539           for (actor->InitPathTraversal (); vtkAssemblyPath* path = actor->GetNextPath (); )
00540           {
00541             vtkSmartPointer<vtkActor> apart = (vtkActor*)path->GetLastNode ()->GetViewProp ();
00542             int psize = apart->GetProperty ()->GetPointSize ();
00543             if (psize > 1)
00544               apart->GetProperty ()->SetPointSize (psize - 1);
00545           }
00546         }
00547       }
00548       break;
00549     }
00550     // Switch between maximize and original window size
00551     case 'f': case 'F':
00552     {
00553       if (keymod)
00554       {
00555         // Get screen size
00556         int *temp = Interactor->GetRenderWindow ()->GetScreenSize ();
00557         int scr_size[2]; scr_size[0] = temp[0]; scr_size[1] = temp[1];
00558 
00559         // Get window size
00560         temp = Interactor->GetRenderWindow ()->GetSize ();
00561         int win_size[2]; win_size[0] = temp[0]; win_size[1] = temp[1];
00562         // Is window size = max?
00563         if (win_size[0] == max_win_height_ && win_size[1] == max_win_width_)
00564         {
00565           // Set the previously saved 'current' window size
00566           Interactor->GetRenderWindow ()->SetSize (win_height_, win_width_);
00567           // Set the previously saved window position
00568           Interactor->GetRenderWindow ()->SetPosition (win_pos_x_, win_pos_y_);
00569           Interactor->GetRenderWindow ()->Render ();
00570           Interactor->Render ();
00571         }
00572         // Set to max
00573         else
00574         {
00575           int *win_pos = Interactor->GetRenderWindow ()->GetPosition ();
00576           // Save the current window position
00577           win_pos_x_  = win_pos[0];
00578           win_pos_y_  = win_pos[1];
00579           // Save the current window size
00580           win_height_ = win_size[0];
00581           win_width_  = win_size[1];
00582           // Set the maximum window size
00583           Interactor->GetRenderWindow ()->SetSize (scr_size[0], scr_size[1]);
00584           Interactor->GetRenderWindow ()->Render ();
00585           Interactor->Render ();
00586           int *win_size = Interactor->GetRenderWindow ()->GetSize ();
00587           // Save the maximum window size
00588           max_win_height_ = win_size[0];
00589           max_win_width_  = win_size[1];
00590         }
00591       }
00592       else
00593       {
00594         AnimState = VTKIS_ANIM_ON;
00595         vtkAssemblyPath *path = NULL;
00596         Interactor->GetPicker ()->Pick (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1], 0.0, CurrentRenderer);
00597         vtkAbstractPropPicker *picker;
00598         if ((picker = vtkAbstractPropPicker::SafeDownCast (Interactor->GetPicker ())))
00599           path = picker->GetPath ();
00600         if (path != NULL)
00601           Interactor->FlyTo (CurrentRenderer, picker->GetPickPosition ());
00602         AnimState = VTKIS_ANIM_OFF;
00603       }
00604       break;
00605     }
00606     // 's'/'S' w/out ALT
00607     case 's': case 'S':
00608     {
00609       if (keymod)
00610       {
00611         int stereo_render = Interactor->GetRenderWindow ()->GetStereoRender ();
00612         if (!stereo_render)
00613         {
00614           if (stereo_anaglyph_mask_default_)
00615           {
00616             Interactor->GetRenderWindow ()->SetAnaglyphColorMask (4, 3);
00617             stereo_anaglyph_mask_default_ = false;
00618           }
00619           else
00620           {
00621             Interactor->GetRenderWindow ()->SetAnaglyphColorMask (2, 5);
00622             stereo_anaglyph_mask_default_ = true;
00623           }
00624         }
00625         Interactor->GetRenderWindow ()->SetStereoRender (!stereo_render);
00626         Interactor->GetRenderWindow ()->Render ();
00627         Interactor->Render ();
00628       }
00629       else
00630         Superclass::OnKeyDown ();
00631       break;
00632     }
00633 
00634     // Display a grid/scale over the screen
00635     case 'g': case 'G':
00636     {
00637       if (!grid_enabled_)
00638       {
00639         grid_actor_->TopAxisVisibilityOn ();
00640         CurrentRenderer->AddViewProp (grid_actor_);
00641         grid_enabled_ = true;
00642       }
00643       else
00644       {
00645         CurrentRenderer->RemoveViewProp (grid_actor_);
00646         grid_enabled_ = false;
00647       }
00648       break;
00649     }
00650 
00651     case 'o': case 'O':
00652     {
00653       vtkSmartPointer<vtkCamera> cam = CurrentRenderer->GetActiveCamera ();
00654       int flag = cam->GetParallelProjection ();
00655       cam->SetParallelProjection (!flag);
00656 
00657       CurrentRenderer->SetActiveCamera (cam);
00658       CurrentRenderer->Render ();
00659       break;
00660     }
00661     // Display a LUT actor on screen
00662     case 'u': case 'U':
00663     {
00664       CloudActorMap::iterator it;
00665       for (it = actors_->begin (); it != actors_->end (); ++it)
00666       {
00667         CloudActor *act = &(*it).second;
00668 
00669         vtkScalarsToColors* lut = act->actor->GetMapper ()->GetLookupTable ();
00670         lut_actor_->SetLookupTable (lut);
00671         lut_actor_->Modified ();
00672       }
00673       if (!lut_enabled_)
00674       {
00675         CurrentRenderer->AddActor (lut_actor_);
00676         lut_actor_->SetVisibility (true);
00677         lut_enabled_ = true;
00678       }
00679       else
00680       {
00681         CurrentRenderer->RemoveActor (lut_actor_);
00682         lut_enabled_ = false;
00683       }
00684       CurrentRenderer->Render ();
00685       break;
00686     }
00687 
00688     // Overwrite the camera reset
00689     case 'r': case 'R':
00690     {
00691       if (!keymod)
00692       {
00693         Superclass::OnKeyDown ();
00694         break;
00695       }
00696 
00697       vtkSmartPointer<vtkCamera> cam = CurrentRenderer->GetActiveCamera ();
00698       static CloudActorMap::iterator it = actors_->begin ();
00699       if (actors_->size () > 0)
00700       {
00701         if (it == actors_->end ())
00702           it = actors_->begin ();
00703 
00704         const CloudActor& actor = it->second;
00705 
00706         cam->SetPosition (actor.viewpoint_transformation_->GetElement (0, 3),
00707                           actor.viewpoint_transformation_->GetElement (1, 3),
00708                           actor.viewpoint_transformation_->GetElement (2, 3));
00709 
00710         cam->SetFocalPoint (actor.viewpoint_transformation_->GetElement (0, 3) - actor.viewpoint_transformation_->GetElement (0, 2),
00711                             actor.viewpoint_transformation_->GetElement (1, 3) - actor.viewpoint_transformation_->GetElement (1, 2),
00712                             actor.viewpoint_transformation_->GetElement (2, 3) - actor.viewpoint_transformation_->GetElement (2, 2));
00713 
00714         cam->SetViewUp (actor.viewpoint_transformation_->GetElement (0, 1),
00715                         actor.viewpoint_transformation_->GetElement (1, 1),
00716                         actor.viewpoint_transformation_->GetElement (2, 1));
00717 
00718         ++it;
00719       }
00720       else
00721       {
00722         cam->SetPosition (0, 0, 0);
00723         cam->SetFocalPoint (0, 0, 1);
00724         cam->SetViewUp (0, -1, 0);
00725       }
00726       CurrentRenderer->SetActiveCamera (cam);
00727       CurrentRenderer->Render ();
00728       break;
00729     }
00730 
00731     case 'q': case 'Q':
00732     {
00733       Interactor->ExitCallback ();
00734       return;
00735     }
00736     default:
00737     {
00738       Superclass::OnKeyDown ();
00739       break;
00740     }
00741   }
00742 
00743   KeyboardEvent event (true, Interactor->GetKeySym (), Interactor->GetKeyCode (), Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00744   keyboard_signal_ (event);
00745 
00746   rens_->Render ();
00747   Interactor->Render ();
00748 }
00749 
00751 void
00752 pcl::visualization::PCLVisualizerInteractorStyle::OnKeyUp ()
00753 {
00754   KeyboardEvent event (false, Interactor->GetKeySym (), Interactor->GetKeyCode (), Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00755   keyboard_signal_ (event);
00756   Superclass::OnKeyUp ();
00757 }
00758 
00760 void
00761 pcl::visualization::PCLVisualizerInteractorStyle::OnMouseMove ()
00762 {
00763   int x = this->Interactor->GetEventPosition()[0];
00764   int y = this->Interactor->GetEventPosition()[1];
00765   MouseEvent event (MouseEvent::MouseMove, MouseEvent::NoButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00766   mouse_signal_ (event);
00767   Superclass::OnMouseMove ();
00768 }
00769 
00771 void
00772 pcl::visualization::PCLVisualizerInteractorStyle::OnLeftButtonDown ()
00773 {
00774 
00775   int x = this->Interactor->GetEventPosition()[0];
00776   int y = this->Interactor->GetEventPosition()[1];
00777 
00778   if (Interactor->GetRepeatCount () == 0)
00779   {
00780     MouseEvent event (MouseEvent::MouseButtonPress, MouseEvent::LeftButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00781     mouse_signal_ (event);
00782   }
00783   else
00784   {
00785     MouseEvent event (MouseEvent::MouseDblClick, MouseEvent::LeftButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00786     mouse_signal_ (event);
00787   }
00788   Superclass::OnLeftButtonDown ();
00789 }
00790 
00792 void
00793 pcl::visualization::PCLVisualizerInteractorStyle::OnLeftButtonUp ()
00794 {
00795   int x = this->Interactor->GetEventPosition()[0];
00796   int y = this->Interactor->GetEventPosition()[1];
00797   MouseEvent event (MouseEvent::MouseButtonRelease, MouseEvent::LeftButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00798   mouse_signal_ (event);
00799   Superclass::OnLeftButtonUp ();
00800 }
00801 
00803 void
00804 pcl::visualization::PCLVisualizerInteractorStyle::OnMiddleButtonDown ()
00805 {
00806   int x = this->Interactor->GetEventPosition()[0];
00807   int y = this->Interactor->GetEventPosition()[1];
00808   if (Interactor->GetRepeatCount () == 0)
00809   {
00810     MouseEvent event (MouseEvent::MouseButtonPress, MouseEvent::MiddleButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00811     mouse_signal_ (event);
00812   }
00813   else
00814   {
00815     MouseEvent event (MouseEvent::MouseDblClick, MouseEvent::MiddleButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00816     mouse_signal_ (event);
00817   }
00818   Superclass::OnMiddleButtonDown ();
00819 }
00820 
00822 void
00823 pcl::visualization::PCLVisualizerInteractorStyle::OnMiddleButtonUp ()
00824 {
00825   int x = this->Interactor->GetEventPosition()[0];
00826   int y = this->Interactor->GetEventPosition()[1];
00827   MouseEvent event (MouseEvent::MouseButtonRelease, MouseEvent::MiddleButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00828   mouse_signal_ (event);
00829   Superclass::OnMiddleButtonUp ();
00830 }
00831 
00833 void
00834 pcl::visualization::PCLVisualizerInteractorStyle::OnRightButtonDown ()
00835 {
00836   int x = this->Interactor->GetEventPosition()[0];
00837   int y = this->Interactor->GetEventPosition()[1];
00838   if (Interactor->GetRepeatCount () == 0)
00839   {
00840     MouseEvent event (MouseEvent::MouseButtonPress, MouseEvent::RightButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00841     mouse_signal_ (event);
00842   }
00843   else
00844   {
00845     MouseEvent event (MouseEvent::MouseDblClick, MouseEvent::RightButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00846     mouse_signal_ (event);
00847   }
00848   Superclass::OnRightButtonDown ();
00849 }
00850 
00852 void
00853 pcl::visualization::PCLVisualizerInteractorStyle::OnRightButtonUp ()
00854 {
00855   int x = this->Interactor->GetEventPosition()[0];
00856   int y = this->Interactor->GetEventPosition()[1];
00857   MouseEvent event (MouseEvent::MouseButtonRelease, MouseEvent::RightButton, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00858   mouse_signal_ (event);
00859   Superclass::OnRightButtonUp ();
00860 }
00861 
00863 void
00864 pcl::visualization::PCLVisualizerInteractorStyle::OnMouseWheelForward ()
00865 {
00866   int x = this->Interactor->GetEventPosition()[0];
00867   int y = this->Interactor->GetEventPosition()[1];
00868   MouseEvent event (MouseEvent::MouseScrollUp, MouseEvent::VScroll, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00869   mouse_signal_ (event);
00870   if (Interactor->GetRepeatCount ())
00871     mouse_signal_ (event);
00872   Superclass::OnMouseWheelForward ();
00873 }
00874 
00876 void
00877 pcl::visualization::PCLVisualizerInteractorStyle::OnMouseWheelBackward ()
00878 {
00879   int x = this->Interactor->GetEventPosition()[0];
00880   int y = this->Interactor->GetEventPosition()[1];
00881   MouseEvent event (MouseEvent::MouseScrollDown, MouseEvent::VScroll, x, y, Interactor->GetAltKey (), Interactor->GetControlKey (), Interactor->GetShiftKey ());
00882   mouse_signal_ (event);
00883   if (Interactor->GetRepeatCount ())
00884     mouse_signal_ (event);
00885   Superclass::OnMouseWheelBackward ();
00886 }
00887 
00889 void
00890 pcl::visualization::PCLVisualizerInteractorStyle::OnTimer ()
00891 {
00892   if (!init_)
00893   {
00894     pcl::console::print_error ("[PCLVisualizerInteractorStyle] Interactor style not initialized. Please call Initialize () before continuing.\n");
00895     return;
00896   }
00897 
00898   if (!rens_)
00899   {
00900     pcl::console::print_error ("[PCLVisualizerInteractorStyle] No renderer collection given! Use SetRendererCollection () before continuing.\n");
00901     return;
00902   }
00903   rens_->Render ();
00904   Interactor->Render ();
00905 }
00906 
00909 void
00910 pcl::visualization::PCLHistogramVisualizerInteractorStyle::Initialize ()
00911 {
00912   init_ = true;
00913 }
00914 
00916 void
00917 pcl::visualization::PCLHistogramVisualizerInteractorStyle::OnKeyDown ()
00918 {
00919   if (!init_)
00920   {
00921     pcl::console::print_error ("[PCLHistogramVisualizerInteractorStyle] Interactor style not initialized. Please call Initialize () before continuing.\n");
00922     return;
00923   }
00924 
00925   FindPokedRenderer (Interactor->GetEventPosition ()[0], Interactor->GetEventPosition ()[1]);
00926 
00927   //fprintf (stderr, "Key sym: %s\n", Interactor->GetKeySym ());
00928   // ---[ Check the rest of the key codes
00929   switch (Interactor->GetKeyCode ())
00930   {
00931     case 'q': case 'Q':
00932     {
00933       Interactor->ExitCallback ();
00934       return;
00935     }
00936     // Switch representation to wireframe
00937     default:
00938     {
00939       Superclass::OnKeyDown ();
00940     }
00941   }
00942   Interactor->Render ();
00943 }
00944 
00946 void
00947 pcl::visualization::PCLHistogramVisualizerInteractorStyle::OnTimer ()
00948 {
00949   if (!init_)
00950   {
00951     pcl::console::print_error ("[PCLHistogramVisualizerInteractorStyle] Interactor style not initialized. Please call Initialize () before continuing.\n");
00952     return;
00953   }
00954 
00955   for (RenWinInteractMap::iterator am_it = wins_.begin (); am_it != wins_.end (); ++am_it)
00956     (*am_it).second.ren_->Render ();
00957 }
00958 
00959 namespace pcl
00960 {
00961   namespace visualization
00962   {
00963     // Standard VTK macro for *New ()
00964     vtkStandardNewMacro (PCLVisualizerInteractorStyle);
00965     vtkStandardNewMacro (PCLHistogramVisualizerInteractorStyle);
00966   }
00967 }
00968 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:30