mouse_event.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) 2011, 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  * Author: Suat Gedikli (gedikli@willowgarage.com)
00037  *
00038  */
00039 
00040 #ifndef PCL_VISUALIZATION_MOUSE_EVENT_H_
00041 #define PCL_VISUALIZATION_MOUSE_EVENT_H_
00042 
00043 #include "keyboard_event.h"
00044 
00045 namespace pcl
00046 {
00047   namespace visualization
00048   {
00049     class MouseEvent
00050     {
00051       public:
00052         typedef enum
00053         {
00054           MouseMove = 1,
00055           MouseButtonPress,
00056           MouseButtonRelease,
00057           MouseScrollDown,
00058           MouseScrollUp,
00059           MouseDblClick
00060         } Type;
00061 
00062         typedef enum
00063         {
00064           NoButton      = 0,
00065           LeftButton,
00066           MiddleButton,
00067           RightButton,
00068           VScroll /*other buttons, scroll wheels etc. may follow*/
00069         } MouseButton;
00070 
00080         inline MouseEvent (const Type& type, const MouseButton& button, 
00081                            unsigned int x, unsigned int y, 
00082                            bool alt, bool ctrl, bool shift);
00083 
00087         inline const Type& 
00088         getType () const;
00089 
00093         inline void 
00094         setType (const Type& type);
00095         
00099         inline const MouseButton& 
00100         getButton () const;
00101 
00103         inline void 
00104         setButton (const MouseButton& button);
00105 
00109         inline unsigned int 
00110         getX () const;
00111 
00115         inline unsigned int 
00116         getY () const;
00117 
00121         inline unsigned int 
00122         getKeyboardModifiers () const;
00123 
00124       protected:
00125         Type type_;
00126         MouseButton button_;
00127         unsigned int pointer_x_;
00128         unsigned int pointer_y_;
00129         unsigned int key_state_;
00130     };
00131 
00132     MouseEvent::MouseEvent (const Type& type, const MouseButton& button,
00133                             unsigned x, unsigned y, 
00134                             bool alt, bool ctrl, bool shift)
00135     : type_ (type)
00136     , button_ (button)
00137     , pointer_x_ (x)
00138     , pointer_y_ (y)
00139     , key_state_ (0)
00140     {
00141       if (alt)
00142         key_state_ = KeyboardEvent::Alt;
00143 
00144       if (ctrl)
00145         key_state_ |= KeyboardEvent::Ctrl;
00146 
00147       if (shift)
00148         key_state_ |= KeyboardEvent::Shift;
00149     }
00150 
00151     const MouseEvent::Type& 
00152     MouseEvent::getType () const
00153     {
00154       return (type_);
00155     }
00156 
00157     void 
00158     MouseEvent::setType (const Type& type)
00159     {
00160       type_ = type;
00161     }
00162     
00163     const MouseEvent::MouseButton& 
00164     MouseEvent::getButton () const
00165     {
00166       return (button_);
00167     }
00168 
00169     void 
00170     MouseEvent::setButton (const MouseButton& button)
00171     {
00172       button_ = button;
00173     }
00174     
00175     unsigned int 
00176     MouseEvent::getX () const
00177     {
00178       return (pointer_x_);
00179     }
00180 
00181     unsigned int 
00182     MouseEvent::getY () const
00183     {
00184       return (pointer_y_);
00185     }
00186 
00187     unsigned int 
00188     MouseEvent::getKeyboardModifiers () const
00189     {
00190       return (key_state_);
00191     }
00192 
00193   } //namespace visualization
00194 } //namespace pcl
00195 
00196 #endif  /* PCL_VISUALIZATION_MOUSE_EVENT_H_ */
00197 


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