interactor.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$
00035  *
00036  */
00037 
00038 #include <vtkVersion.h>
00039 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00040 
00041 #include <pcl/visualization/interactor.h>
00042 #include <vtkCommand.h>
00043 
00044 namespace pcl
00045 {
00046   namespace visualization
00047   {
00048     // Standard VTK macro for *New () 
00049     vtkStandardNewMacro (PCLVisualizerInteractor);
00050     
00051 /*    void
00052     PCLVisualizerInteractor::TerminateApp ()
00053     {
00054       stopped = true;
00055     }
00056 */    
00058     void 
00059     PCLVisualizerInteractor::stopLoop ()
00060     {
00061   #if defined (_WIN32) || defined (VTK_USE_COCOA) || defined (VTK_USE_CARBON)
00062       BreakLoopFlagOn ();
00063       // Send a VTK_BreakWin32Loop ClientMessage event to be sure we pop out of the
00064       // event loop.  This "wakes up" the event loop.  Otherwise, it might sit idle
00065       // waiting for an event before realizing an exit was requested.
00066     #if defined (_WIN32)
00067       SendMessage (this->WindowId, RegisterWindowMessage (TEXT ("VTK_BreakWin32Loop")), 0, 0);
00068     #endif
00069   #else
00070       BreakLoopFlagOn ();
00071       XClientMessageEvent client;
00072       memset (&client, 0, sizeof (client));
00073       client.type = ClientMessage;
00074       client.display = DisplayId;
00075       client.window = WindowId;
00076       client.message_type = XInternAtom (client.display, "spinOnce exit", false);
00077       client.format = 32; // indicates size of data chunks: 8, 16 or 32 bits...
00078       XSendEvent (client.display, client.window, True, NoEventMask, reinterpret_cast<XEvent *>(&client));
00079       XFlush (client.display);
00080   #endif
00081     }
00082 
00083   #if defined (_WIN32) || (defined VTK_USE_COCOA) || defined (VTK_USE_CARBON)
00084 
00085     void 
00086     PCLVisualizerInteractor::Start ()
00087     {
00088       // Let the compositing handle the event loop if it wants to.
00089       if (this->HasObserver(vtkCommand::StartEvent) && !this->HandleEventLoop)
00090       {
00091         this->InvokeEvent (vtkCommand::StartEvent, NULL);
00092         return;
00093       }
00094 
00095       // No need to do anything if this is a 'mapped' interactor
00096       if (!this->Enabled || !this->InstallMessageProc)
00097         return;
00098 
00099       this->StartedMessageLoop = 1;
00100 
00101       MSG msg;
00102       this->BreakLoopFlag=0;
00103       
00104       while (GetMessage (&msg, NULL, 0, 0) && this->BreakLoopFlag == 0)
00105       {
00106         TranslateMessage (&msg);
00107         DispatchMessage (&msg);
00108       }
00109     }
00110 
00112     void 
00113     PCLVisualizerInteractor::SetBreakLoopFlag (int f)
00114     {
00115       if (f)
00116         this->BreakLoopFlagOn ();
00117       else
00118         this->BreakLoopFlagOff ();
00119     }
00120 
00122     void 
00123     PCLVisualizerInteractor::BreakLoopFlagOff ()
00124     {
00125       this->BreakLoopFlag = 0;
00126       this->Modified ();
00127     }
00128 
00130     void 
00131     PCLVisualizerInteractor::BreakLoopFlagOn ()
00132     {
00133       this->BreakLoopFlag = 1;
00134       this->Modified ();
00135     }
00136   #endif
00137   }
00138 }
00139 
00140 #endif


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