window.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) 2009-2012, 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 <vtkSmartPointer.h>
00040 #include <vtkCallbackCommand.h>
00041 #include <vtkRenderWindowInteractor.h>
00042 #include <vtkRenderWindow.h>
00043 #include <vtkRendererCollection.h>
00044 #include <pcl/visualization/interactor_style.h>
00045 
00046 #include <pcl/visualization/window.h>
00047 #include <pcl/visualization/keyboard_event.h>
00048 #include <pcl/visualization/mouse_event.h>
00049 #include <pcl/common/time.h>
00050 
00052 pcl::visualization::Window::Window (const std::string& window_name)
00053   : stopped_ ()
00054   , timer_id_ ()
00055   , mouse_signal_ ()
00056   , keyboard_signal_ ()
00057   , win_ ()
00058   , interactor_ ()
00059   , mouse_command_ (vtkCallbackCommand::New ())
00060   , keyboard_command_ (vtkCallbackCommand::New ())
00061   , style_ (vtkSmartPointer<pcl::visualization::PCLVisualizerInteractorStyle>::New ())
00062   , rens_ (vtkSmartPointer<vtkRendererCollection>::New ())
00063   , exit_main_loop_timer_callback_ ()
00064   , exit_callback_ ()
00065 
00066 {
00067   mouse_command_->SetClientData (this);
00068   mouse_command_->SetCallback (Window::MouseCallback);
00069 
00070   keyboard_command_->SetClientData (this);
00071   keyboard_command_->SetCallback (Window::KeyboardCallback);
00072 
00073   // Create a RendererWindow
00074   win_ = vtkSmartPointer<vtkRenderWindow>::New ();
00075   win_->SetWindowName (window_name.c_str ());
00076   win_->AlphaBitPlanesOff ();
00077   win_->PointSmoothingOff ();
00078   win_->LineSmoothingOff ();
00079   win_->PolygonSmoothingOff ();
00080   win_->SwapBuffersOn ();
00081   win_->SetStereoTypeToAnaglyph ();
00082 
00083   // Get screen size
00084   int *scr_size = win_->GetScreenSize ();
00085   // Set the window size as 1/2 of the screen size
00086   win_->SetSize (scr_size[0] / 2, scr_size[1] / 2);
00087 
00088   // Create the interactor style
00089   style_->Initialize ();
00090   style_->setRendererCollection (rens_);
00091   style_->UseTimersOn ();
00092 
00093   // Create the interactor
00094   interactor_ = vtkSmartPointer<vtkRenderWindowInteractor>::New ();
00095   //interactor_ = vtkSmartPointer<PCLVisualizerInteractor>::New ();
00096 
00097   interactor_->SetRenderWindow (win_);
00098   interactor_->SetInteractorStyle (style_);
00099   interactor_->SetDesiredUpdateRate (30.0);
00100   // Initialize and create timer
00101   interactor_->Initialize ();
00102   //interactor_->CreateRepeatingTimer (5000L);
00103   timer_id_ = interactor_->CreateRepeatingTimer (5000L);
00104   //  interactor_->timer_id_ = interactor_->CreateRepeatingTimer (5000L);
00105   //interactor_->timer_id_ = interactor_->CreateRepeatingTimer (30L);
00106 
00107   exit_main_loop_timer_callback_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
00108   exit_main_loop_timer_callback_->window = this;
00109   exit_main_loop_timer_callback_->right_timer_id = -1;
00110   interactor_->AddObserver (vtkCommand::TimerEvent, exit_main_loop_timer_callback_);
00111 
00112   exit_callback_ = vtkSmartPointer<ExitCallback>::New ();
00113   exit_callback_->window = this;
00114   interactor_->AddObserver (vtkCommand::ExitEvent, exit_callback_);
00115 
00116   resetStoppedFlag ();
00117 }
00118 
00120 pcl::visualization::Window::Window (const pcl::visualization::Window &src)
00121   : stopped_ (src.stopped_)
00122   , timer_id_ (src.timer_id_)
00123   //, mouse_signal_ (src.mouse_signal_)
00124   //, keyboard_signal_ (src.keyboard_signal_)
00125   , win_ (src.win_)
00126   , interactor_ (src.interactor_)
00127   , mouse_command_ (src.mouse_command_)
00128   , keyboard_command_ (src.keyboard_command_)
00129   , style_ (src.style_)
00130   , rens_ (src.rens_)
00131   , exit_main_loop_timer_callback_ (src.exit_main_loop_timer_callback_)
00132   , exit_callback_ (src.exit_callback_)
00133 {
00134 }
00135 
00137 pcl::visualization::Window&
00138 pcl::visualization::Window::operator = (const pcl::visualization::Window &src)
00139 {
00140   stopped_ = src.stopped_;
00141   timer_id_ = src.timer_id_;
00142   //mouse_signal_ = src.mouse_signal_;
00143   //keyboard_signal_ = src.keyboard_signal_;
00144   win_ = src.win_;
00145   interactor_ = src.interactor_;
00146   mouse_command_ = src.mouse_command_;
00147   keyboard_command_ = src.keyboard_command_;
00148   style_ = src.style_;
00149   rens_ = src.rens_;
00150   exit_main_loop_timer_callback_ = src.exit_main_loop_timer_callback_;
00151   exit_callback_ = src.exit_callback_;
00152   return (*this);
00153 }
00154 
00156 pcl::visualization::Window::~Window ()
00157 {
00158   interactor_->DestroyTimer (timer_id_);
00159   //  interactor_->DestroyTimer (interactor_->timer_id_);
00160 }
00161 
00163 void 
00164 pcl::visualization::Window::spin ()
00165 {
00166   resetStoppedFlag ();
00167   // Render the window before we start the interactor
00168   win_->Render ();
00169   interactor_->Start ();
00170 }
00171 
00173 void
00174 pcl::visualization::Window::spinOnce (int time, bool force_redraw)
00175 {
00176   resetStoppedFlag ();
00177 
00178   if (time <= 0)
00179     time = 1;
00180 
00181   if (force_redraw)
00182   {
00183     interactor_->Render ();
00184     exit_main_loop_timer_callback_->right_timer_id = interactor_->CreateRepeatingTimer (time);
00185     interactor_->Start ();
00186     interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00187     return;
00188   }
00189 
00190   DO_EVERY(1.0/interactor_->GetDesiredUpdateRate (),
00191     interactor_->Render ();
00192     exit_main_loop_timer_callback_->right_timer_id = interactor_->CreateRepeatingTimer (time);
00193     interactor_->Start ();
00194     interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00195   );
00196 }
00197 
00199 boost::signals2::connection 
00200 pcl::visualization::Window::registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> callback)
00201 {
00202   // just add observer at first time when a callback is registered
00203   if (mouse_signal_.empty ())
00204   {
00205     interactor_->AddObserver (vtkCommand::MouseMoveEvent, mouse_command_);
00206     interactor_->AddObserver (vtkCommand::MiddleButtonPressEvent, mouse_command_);
00207     interactor_->AddObserver (vtkCommand::MiddleButtonReleaseEvent, mouse_command_);
00208     interactor_->AddObserver (vtkCommand::MouseWheelBackwardEvent, mouse_command_);
00209     interactor_->AddObserver (vtkCommand::MouseWheelForwardEvent, mouse_command_);
00210     interactor_->AddObserver (vtkCommand::LeftButtonPressEvent, mouse_command_);
00211     interactor_->AddObserver (vtkCommand::LeftButtonReleaseEvent, mouse_command_);
00212     interactor_->AddObserver (vtkCommand::RightButtonPressEvent, mouse_command_);
00213     interactor_->AddObserver (vtkCommand::RightButtonReleaseEvent, mouse_command_);
00214   }
00215   return (mouse_signal_.connect (callback));
00216 }
00217 
00219 boost::signals2::connection 
00220 pcl::visualization::Window::registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> callback)
00221 {
00222   // just add observer at first time when a callback is registered
00223   if (keyboard_signal_.empty ())
00224   {
00225     interactor_->AddObserver (vtkCommand::KeyPressEvent, keyboard_command_);
00226     interactor_->AddObserver (vtkCommand::KeyReleaseEvent, keyboard_command_);
00227   }
00228 
00229   return (keyboard_signal_.connect (callback));
00230 }
00231 
00233 void 
00234 pcl::visualization::Window::emitMouseEvent (unsigned long event_id)
00235 {
00236   int x,y;
00237   interactor_->GetMousePosition (&x, &y);
00238   MouseEvent event (MouseEvent::MouseMove, MouseEvent::NoButton, x, y, interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
00239   bool repeat = false;
00240   switch (event_id)
00241   {
00242     case vtkCommand::MouseMoveEvent :
00243       event.setType(MouseEvent::MouseMove);
00244       break;
00245     
00246     case vtkCommand::LeftButtonPressEvent :
00247       event.setButton(MouseEvent::LeftButton);
00248       if (interactor_->GetRepeatCount () == 0)
00249         event.setType(MouseEvent::MouseButtonPress);
00250       else
00251         event.setType(MouseEvent::MouseDblClick);
00252       break;
00253       
00254     case vtkCommand::LeftButtonReleaseEvent :
00255       event.setButton(MouseEvent::LeftButton);
00256       event.setType(MouseEvent::MouseButtonRelease);
00257       break;
00258       
00259     case vtkCommand::RightButtonPressEvent :
00260       event.setButton(MouseEvent::RightButton);
00261       if (interactor_->GetRepeatCount () == 0)
00262         event.setType(MouseEvent::MouseButtonPress);
00263       else
00264         event.setType(MouseEvent::MouseDblClick);
00265       break;
00266       
00267     case vtkCommand::RightButtonReleaseEvent :
00268       event.setButton(MouseEvent::RightButton);
00269       event.setType(MouseEvent::MouseButtonRelease);
00270       break;
00271       
00272     case vtkCommand::MiddleButtonPressEvent :
00273       event.setButton(MouseEvent::MiddleButton);
00274       if (interactor_->GetRepeatCount () == 0)
00275         event.setType(MouseEvent::MouseButtonPress);
00276       else
00277         event.setType(MouseEvent::MouseDblClick);
00278       break;
00279       
00280     case vtkCommand::MiddleButtonReleaseEvent :
00281       event.setButton(MouseEvent::MiddleButton);
00282       event.setType(MouseEvent::MouseButtonRelease);
00283       break;
00284       
00285       case vtkCommand::MouseWheelBackwardEvent :
00286       event.setButton(MouseEvent::VScroll);
00287       event.setType(MouseEvent::MouseScrollDown);
00288       if (interactor_->GetRepeatCount () != 0)
00289         repeat = true;
00290       break;
00291       
00292     case vtkCommand::MouseWheelForwardEvent :
00293       event.setButton(MouseEvent::VScroll);
00294       event.setType(MouseEvent::MouseScrollUp);
00295       if (interactor_->GetRepeatCount () != 0)
00296         repeat = true;
00297       break;
00298     default:
00299       return;
00300   }
00301 
00302   mouse_signal_ (event);
00303   if (repeat)
00304     mouse_signal_ (event);
00305 }
00306 
00308 void 
00309 pcl::visualization::Window::emitKeyboardEvent (unsigned long event_id)
00310 {
00311   KeyboardEvent event (bool(event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
00312   keyboard_signal_ (event);
00313 }
00314 
00316 void 
00317 pcl::visualization::Window::MouseCallback(vtkObject*, unsigned long eid, void* clientdata, void*)
00318 {
00319   Window* window = reinterpret_cast<Window*> (clientdata);
00320   window->emitMouseEvent (eid);
00321 }
00322 
00324 void 
00325 pcl::visualization::Window::KeyboardCallback (vtkObject*, unsigned long eid, void* clientdata, void*)
00326 {
00327   Window* window = reinterpret_cast<Window*> (clientdata);
00328   window->emitKeyboardEvent (eid);
00329 }
00330 
00332 pcl::visualization::Window::ExitMainLoopTimerCallback::ExitMainLoopTimerCallback () 
00333   : right_timer_id (), window () 
00334 {
00335 }
00336 
00338 pcl::visualization::Window::ExitMainLoopTimerCallback::ExitMainLoopTimerCallback (
00339     const pcl::visualization::Window::ExitMainLoopTimerCallback& src) 
00340   : vtkCommand (), right_timer_id (src.right_timer_id), window (src.window) 
00341 {
00342 }
00343 
00345 pcl::visualization::Window::ExitMainLoopTimerCallback&
00346 pcl::visualization::Window::ExitMainLoopTimerCallback::operator = (
00347     const pcl::visualization::Window::ExitMainLoopTimerCallback& src) 
00348 { 
00349   right_timer_id = src.right_timer_id; 
00350   window = src.window; 
00351   return (*this); 
00352 }
00353 
00355 void
00356 pcl::visualization::Window::ExitMainLoopTimerCallback::Execute (
00357     vtkObject*, unsigned long event_id, void* call_data)
00358 {
00359   if (event_id != vtkCommand::TimerEvent)
00360     return;
00361   int timer_id = *static_cast<int*> (call_data);
00362   if (timer_id != right_timer_id)
00363     return;
00364   window->interactor_->TerminateApp ();
00365 //            window->interactor_->stopLoop ();
00366 }
00367 
00369 pcl::visualization::Window::ExitCallback::ExitCallback () 
00370   : window () 
00371 {
00372 }
00373 
00375 pcl::visualization::Window::ExitCallback::ExitCallback (
00376     const pcl::visualization::Window::ExitCallback &src) 
00377   : vtkCommand (), window (src.window)
00378 {
00379 }
00380 
00382 pcl::visualization::Window::ExitCallback&
00383 pcl::visualization::Window::ExitCallback::operator = (
00384     const pcl::visualization::Window::ExitCallback &src) 
00385 {
00386   window = src.window; 
00387   return (*this);
00388 }
00389 
00391 void
00392 pcl::visualization::Window::ExitCallback::Execute (
00393     vtkObject*, unsigned long event_id, void*)
00394 {
00395   if (event_id != vtkCommand::ExitEvent)
00396     return;
00397   window->interactor_->TerminateApp ();
00398   window->stopped_ = true;
00399 }
00400 


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