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  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: vtk.h 3779 2012-01-03 07:25:01Z rusu $
00037  */
00038 
00039 #include <pcl/visualization/window.h>
00040 #include <pcl/visualization/keyboard_event.h>
00041 #include <pcl/visualization/mouse_event.h>
00042 #include <pcl/common/time.h>
00043 
00045 pcl::visualization::Window::Window (const std::string& window_name)
00046   : stopped_ ()
00047   , timer_id_ ()
00048   , mouse_signal_ ()
00049   , keyboard_signal_ ()
00050   , win_ ()
00051   , interactor_ ()
00052   , mouse_command_ (vtkCallbackCommand::New ())
00053   , keyboard_command_ (vtkCallbackCommand::New ())
00054   , style_ (vtkSmartPointer<pcl::visualization::PCLVisualizerInteractorStyle>::New ())
00055   , rens_ (vtkSmartPointer<vtkRendererCollection>::New ())
00056   , exit_main_loop_timer_callback_ ()
00057   , exit_callback_ ()
00058 
00059 {
00060   mouse_command_->SetClientData (this);
00061   mouse_command_->SetCallback (Window::MouseCallback);
00062 
00063   keyboard_command_->SetClientData (this);
00064   keyboard_command_->SetCallback (Window::KeyboardCallback);
00065 
00066   // Create a RendererWindow
00067   win_ = vtkSmartPointer<vtkRenderWindow>::New ();
00068   win_->SetWindowName (window_name.c_str ());
00069   win_->AlphaBitPlanesOff ();
00070   win_->PointSmoothingOff ();
00071   win_->LineSmoothingOff ();
00072   win_->PolygonSmoothingOff ();
00073   win_->SwapBuffersOn ();
00074   win_->SetStereoTypeToAnaglyph ();
00075 
00076   // Get screen size
00077   int *scr_size = win_->GetScreenSize ();
00078   // Set the window size as 1/2 of the screen size
00079   win_->SetSize (scr_size[0] / 2, scr_size[1] / 2);
00080 
00081   // Create the interactor style
00082   style_->Initialize ();
00083   style_->setRendererCollection (rens_);
00084   style_->UseTimersOn ();
00085 
00086   // Create the interactor
00087   interactor_ = vtkSmartPointer<vtkRenderWindowInteractor>::New ();
00088   //interactor_ = vtkSmartPointer<PCLVisualizerInteractor>::New ();
00089 
00090   interactor_->SetRenderWindow (win_);
00091   interactor_->SetInteractorStyle (style_);
00092   interactor_->SetDesiredUpdateRate (30.0);
00093   // Initialize and create timer
00094   interactor_->Initialize ();
00095   //interactor_->CreateRepeatingTimer (5000L);
00096   timer_id_ = interactor_->CreateRepeatingTimer (5000L);
00097   //  interactor_->timer_id_ = interactor_->CreateRepeatingTimer (5000L);
00098   //interactor_->timer_id_ = interactor_->CreateRepeatingTimer (30L);
00099 
00100   exit_main_loop_timer_callback_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
00101   exit_main_loop_timer_callback_->window = this;
00102   exit_main_loop_timer_callback_->right_timer_id = -1;
00103   interactor_->AddObserver (vtkCommand::TimerEvent, exit_main_loop_timer_callback_);
00104 
00105   exit_callback_ = vtkSmartPointer<ExitCallback>::New ();
00106   exit_callback_->window = this;
00107   interactor_->AddObserver (vtkCommand::ExitEvent, exit_callback_);
00108 
00109   resetStoppedFlag ();
00110 }
00111 
00113 pcl::visualization::Window::Window (const pcl::visualization::Window &src)
00114   : stopped_ (src.stopped_)
00115   , timer_id_ (src.timer_id_)
00116   //, mouse_signal_ (src.mouse_signal_)
00117   //, keyboard_signal_ (src.keyboard_signal_)
00118   , win_ (src.win_)
00119   , interactor_ (src.interactor_)
00120   , mouse_command_ (src.mouse_command_)
00121   , keyboard_command_ (src.keyboard_command_)
00122   , style_ (src.style_)
00123   , rens_ (src.rens_)
00124   , exit_main_loop_timer_callback_ (src.exit_main_loop_timer_callback_)
00125   , exit_callback_ (src.exit_callback_)
00126 {
00127 }
00128 
00130 pcl::visualization::Window&
00131 pcl::visualization::Window::operator = (const pcl::visualization::Window &src)
00132 {
00133   stopped_ = src.stopped_;
00134   timer_id_ = src.timer_id_;
00135   //mouse_signal_ = src.mouse_signal_;
00136   //keyboard_signal_ = src.keyboard_signal_;
00137   win_ = src.win_;
00138   interactor_ = src.interactor_;
00139   mouse_command_ = src.mouse_command_;
00140   keyboard_command_ = src.keyboard_command_;
00141   style_ = src.style_;
00142   rens_ = src.rens_;
00143   exit_main_loop_timer_callback_ = src.exit_main_loop_timer_callback_;
00144   exit_callback_ = src.exit_callback_;
00145   return (*this);
00146 }
00147 
00149 pcl::visualization::Window::~Window ()
00150 {
00151   interactor_->DestroyTimer (timer_id_);
00152   //  interactor_->DestroyTimer (interactor_->timer_id_);
00153 }
00154 
00156 void 
00157 pcl::visualization::Window::spin ()
00158 {
00159   resetStoppedFlag ();
00160   // Render the window before we start the interactor
00161   win_->Render ();
00162   interactor_->Start ();
00163 }
00164 
00166 void
00167 pcl::visualization::Window::spinOnce (int time, bool force_redraw)
00168 {
00169   resetStoppedFlag ();
00170 
00171   if (time <= 0)
00172     time = 1;
00173 
00174   if (force_redraw)
00175   {
00176     interactor_->Render ();
00177     exit_main_loop_timer_callback_->right_timer_id = interactor_->CreateRepeatingTimer (time);
00178     interactor_->Start ();
00179     interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00180     return;
00181   }
00182 
00183   DO_EVERY(1.0/interactor_->GetDesiredUpdateRate (),
00184     interactor_->Render ();
00185     exit_main_loop_timer_callback_->right_timer_id = interactor_->CreateRepeatingTimer (time);
00186     interactor_->Start ();
00187     interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id);
00188   );
00189 }
00190 
00192 boost::signals2::connection 
00193 pcl::visualization::Window::registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> callback)
00194 {
00195   // just add observer at first time when a callback is registered
00196   if (mouse_signal_.empty ())
00197   {
00198     interactor_->AddObserver (vtkCommand::MouseMoveEvent, mouse_command_);
00199     interactor_->AddObserver (vtkCommand::MiddleButtonPressEvent, mouse_command_);
00200     interactor_->AddObserver (vtkCommand::MiddleButtonReleaseEvent, mouse_command_);
00201     interactor_->AddObserver (vtkCommand::MouseWheelBackwardEvent, mouse_command_);
00202     interactor_->AddObserver (vtkCommand::MouseWheelForwardEvent, mouse_command_);
00203     interactor_->AddObserver (vtkCommand::LeftButtonPressEvent, mouse_command_);
00204     interactor_->AddObserver (vtkCommand::LeftButtonReleaseEvent, mouse_command_);
00205     interactor_->AddObserver (vtkCommand::RightButtonPressEvent, mouse_command_);
00206     interactor_->AddObserver (vtkCommand::RightButtonReleaseEvent, mouse_command_);
00207   }
00208   return (mouse_signal_.connect (callback));
00209 }
00210 
00212 boost::signals2::connection 
00213 pcl::visualization::Window::registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> callback)
00214 {
00215   // just add observer at first time when a callback is registered
00216   if (keyboard_signal_.empty ())
00217   {
00218     interactor_->AddObserver (vtkCommand::KeyPressEvent, keyboard_command_);
00219     interactor_->AddObserver (vtkCommand::KeyReleaseEvent, keyboard_command_);
00220   }
00221 
00222   return (keyboard_signal_.connect (callback));
00223 }
00224 
00226 void 
00227 pcl::visualization::Window::emitMouseEvent (unsigned long event_id)
00228 {
00229   int x,y;
00230   interactor_->GetMousePosition (&x, &y);
00231   MouseEvent event (MouseEvent::MouseMove, MouseEvent::NoButton, x, y, interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
00232   bool repeat = false;
00233   switch (event_id)
00234   {
00235     case vtkCommand::MouseMoveEvent :
00236       event.setType(MouseEvent::MouseMove);
00237       break;
00238     
00239     case vtkCommand::LeftButtonPressEvent :
00240       event.setButton(MouseEvent::LeftButton);
00241       if (interactor_->GetRepeatCount () == 0)
00242         event.setType(MouseEvent::MouseButtonPress);
00243       else
00244         event.setType(MouseEvent::MouseDblClick);
00245       break;
00246       
00247     case vtkCommand::LeftButtonReleaseEvent :
00248       event.setButton(MouseEvent::LeftButton);
00249       event.setType(MouseEvent::MouseButtonRelease);
00250       break;
00251       
00252     case vtkCommand::RightButtonPressEvent :
00253       event.setButton(MouseEvent::RightButton);
00254       if (interactor_->GetRepeatCount () == 0)
00255         event.setType(MouseEvent::MouseButtonPress);
00256       else
00257         event.setType(MouseEvent::MouseDblClick);
00258       break;
00259       
00260     case vtkCommand::RightButtonReleaseEvent :
00261       event.setButton(MouseEvent::RightButton);
00262       event.setType(MouseEvent::MouseButtonRelease);
00263       break;
00264       
00265     case vtkCommand::MiddleButtonPressEvent :
00266       event.setButton(MouseEvent::MiddleButton);
00267       if (interactor_->GetRepeatCount () == 0)
00268         event.setType(MouseEvent::MouseButtonPress);
00269       else
00270         event.setType(MouseEvent::MouseDblClick);
00271       break;
00272       
00273     case vtkCommand::MiddleButtonReleaseEvent :
00274       event.setButton(MouseEvent::MiddleButton);
00275       event.setType(MouseEvent::MouseButtonRelease);
00276       break;
00277       
00278       case vtkCommand::MouseWheelBackwardEvent :
00279       event.setButton(MouseEvent::VScroll);
00280       event.setType(MouseEvent::MouseScrollDown);
00281       if (interactor_->GetRepeatCount () != 0)
00282         repeat = true;
00283       break;
00284       
00285     case vtkCommand::MouseWheelForwardEvent :
00286       event.setButton(MouseEvent::VScroll);
00287       event.setType(MouseEvent::MouseScrollUp);
00288       if (interactor_->GetRepeatCount () != 0)
00289         repeat = true;
00290       break;
00291     default:
00292       return;
00293   }
00294 
00295   mouse_signal_ (event);
00296   if (repeat)
00297     mouse_signal_ (event);
00298 }
00299 
00301 void 
00302 pcl::visualization::Window::emitKeyboardEvent (unsigned long event_id)
00303 {
00304   KeyboardEvent event (bool(event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
00305   keyboard_signal_ (event);
00306 }
00307 
00309 void 
00310 pcl::visualization::Window::MouseCallback(vtkObject*, unsigned long eid, void* clientdata, void*)
00311 {
00312   Window* window = reinterpret_cast<Window*> (clientdata);
00313   window->emitMouseEvent (eid);
00314 }
00315 
00317 void 
00318 pcl::visualization::Window::KeyboardCallback (vtkObject*, unsigned long eid, void* clientdata, void*)
00319 {
00320   Window* window = reinterpret_cast<Window*> (clientdata);
00321   window->emitKeyboardEvent (eid);
00322 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:12