window.h
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: window.h 5368 2012-03-28 04:27:59Z nizar $
00037  *
00038  */
00039 
00040 #ifndef PCL_VISUALIZER_WINDOW_H__
00041 #define PCL_VISUALIZER_WINDOW_H__
00042 
00043 #include <pcl/pcl_macros.h>
00044 #include <pcl/console/print.h>
00045 #include <pcl/visualization/vtk.h>
00046 #include <pcl/visualization/interactor_style.h>
00047 
00048 namespace pcl
00049 {
00050   namespace visualization
00051   {
00052     class MouseEvent;
00053     class KeyboardEvent;
00054 
00055     class PCL_EXPORTS Window
00056     {
00057       public:
00058         Window (const std::string& window_name = "");
00059         Window (const Window &src);
00060         Window& operator = (const Window &src);
00061 
00062         virtual ~Window ();
00063 
00065         void
00066         spin ();
00067 
00073         void
00074         spinOnce (int time = 1, bool force_redraw = false);
00075 
00077         bool
00078         wasStopped () const { return (stopped_); }
00079 
00086         boost::signals2::connection
00087         registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*),
00088                                   void* cookie = NULL)
00089         {
00090           return registerKeyboardCallback (boost::bind (callback, _1, cookie));
00091         }
00092 
00100         template<typename T> boost::signals2::connection
00101         registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*),
00102                                   T& instance, void* cookie = NULL)
00103         {
00104           return registerKeyboardCallback (boost::bind (callback,  boost::ref (instance), _1, cookie));
00105         }
00106 
00113         boost::signals2::connection
00114         registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*),
00115                                void* cookie = NULL)
00116         {
00117           return registerMouseCallback (boost::bind (callback, _1, cookie));
00118         }
00119 
00127         template<typename T> boost::signals2::connection
00128         registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*),
00129                                T& instance, void* cookie = NULL)
00130         {
00131           return registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie));
00132         }
00133 
00134       protected: // methods
00135 
00137         void
00138         resetStoppedFlag () { stopped_ = false; }
00139 
00145         boost::signals2::connection
00146         registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> );
00147 
00153         boost::signals2::connection
00154         registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> );
00155 
00156         void
00157         emitMouseEvent (unsigned long event_id);
00158 
00159         void
00160         emitKeyboardEvent (unsigned long event_id);
00161 
00162         // Callbacks used to register for vtk command
00163         static void
00164         MouseCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata);
00165         static void
00166         KeyboardCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata);
00167 
00168       protected: // types
00169         struct ExitMainLoopTimerCallback : public vtkCommand
00170         {
00171           static ExitMainLoopTimerCallback* New()
00172           {
00173             return (new ExitMainLoopTimerCallback);
00174           }
00175 
00176           ExitMainLoopTimerCallback () : right_timer_id (), window () {}
00177           ExitMainLoopTimerCallback (const ExitMainLoopTimerCallback& src) : vtkCommand (), right_timer_id (src.right_timer_id), window (src.window) {}
00178           ExitMainLoopTimerCallback& operator = (const ExitMainLoopTimerCallback& src) { right_timer_id = src.right_timer_id; window = src.window; return (*this); }
00179 
00180           virtual void 
00181           Execute (vtkObject*, unsigned long event_id, void* call_data)
00182           {
00183             if (event_id != vtkCommand::TimerEvent)
00184               return;
00185             int timer_id = *static_cast<int*> (call_data);
00186             //PCL_WARN ("[pcl::visualization::Window::ExitMainLoopTimerCallback] Timer %d called.\n", timer_id);
00187             if (timer_id != right_timer_id)
00188               return;
00189             window->interactor_->TerminateApp ();
00190 //            window->interactor_->stopLoop ();
00191           }
00192           int right_timer_id;
00193           Window* window;
00194         };
00195 
00196         struct ExitCallback : public vtkCommand
00197         {
00198           static ExitCallback* New ()
00199           {
00200             return (new ExitCallback);
00201           }
00202 
00203           ExitCallback () : window () {}
00204           ExitCallback (const ExitCallback &src) : vtkCommand (), window (src.window) {}
00205           ExitCallback& operator = (const ExitCallback &src) { window = src.window; return (*this); }
00206  
00207           virtual void 
00208           Execute (vtkObject*, unsigned long event_id, void*)
00209           {
00210             if (event_id != vtkCommand::ExitEvent)
00211               return;
00212             window->interactor_->TerminateApp ();
00213             window->stopped_ = true;
00214           }
00215           Window* window;
00216         };
00217 
00218         bool stopped_;
00219         int timer_id_;
00220 
00221     protected: // member fields
00222         boost::signals2::signal<void (const pcl::visualization::MouseEvent&)> mouse_signal_;
00223         boost::signals2::signal<void (const pcl::visualization::KeyboardEvent&)> keyboard_signal_;
00224 
00225         vtkSmartPointer<vtkRenderWindow> win_;
00226         vtkSmartPointer<vtkRenderWindowInteractor> interactor_;
00227         vtkCallbackCommand* mouse_command_;
00228         vtkCallbackCommand* keyboard_command_;
00230         vtkSmartPointer<PCLVisualizerInteractorStyle> style_;
00232         vtkSmartPointer<vtkRendererCollection> rens_;
00233         vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
00234         vtkSmartPointer<ExitCallback> exit_callback_;
00235     };
00236   }
00237 }
00238 
00239 #endif  /* __WINDOW_H__ */
00240 


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