$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2011, Robert Bosch LLC. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Robert Bosch nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 *********************************************************************/ 00036 #ifndef GLWIDGET_H 00037 #define GLWIDGET_H 00038 00039 #define _USE_MATH_DEFINES 00040 00041 #include <cmath> 00042 00043 #include <QtOpenGL/QGLWidget> 00044 #include <QtCore/QTimer> 00045 00046 namespace vlr { 00047 00048 #define DEFAULT_ZOOM_SENSITIVITY 0.2 00049 #define DEFAULT_ROTATE_SENSITIVITY 0.50 00050 #define DEFAULT_MOVE_SENSITIVITY 0.001 00051 #define DEFAULT_MIN_ZOOM_RANGE 0.5 00052 #define DEFAULT_CAMERA_FOV 30.0 00053 #define DEFAULT_MIN_CLIP_RANGE 1.0 00054 #define DEFAULT_MAX_CLIP_RANGE 400.0 00055 #define DEFAULT_FPS 30.0 00056 00057 #define DISPLAY_REFRESH_DELAY_MS 66.6666666667 // ~(15 Hz) 00058 00059 #define KEY_ROTATE_AMOUNT 5.0 00060 #define KEY_MOVE_AMOUNT 10.0 00061 #define KEY_ZOOM_AMOUNT 5.0 00062 00063 #ifndef CAMERA_STATE_DEFINED 00064 #define CAMERA_STATE_DEFINED 00065 typedef enum {IDLE, ROTATING, MOVING, ZOOMING} CameraState; 00066 #else 00067 typedef camera_state_t CameraState; 00068 #endif 00069 00070 typedef void (*DisplayFunction)(void); 00071 typedef void (*KeyboardFunction)(unsigned char, int, int); 00072 typedef void (*MouseFunction)(int, int, int, int); 00073 typedef void (*MotionFunction)(int, int); 00074 00075 template<class T> inline T rad(T x) {return T(x*M_PI/180.0);} 00076 00077 typedef struct 00078 { 00079 CameraState state; 00080 double pan, tilt, distance; 00081 double xOffset, yOffset, zOffset; 00082 double zoom, warp_x, warp_y; 00083 } cameraPose_t, *cameraPose_p; 00084 00085 class GLWidget : public QGLWidget 00086 { 00087 Q_OBJECT 00088 00089 protected: 00090 QTimer timer; 00091 int windowID; 00092 int windowWidth, windowHeight; 00093 double fps; 00094 cameraPose_t cameraPose; 00095 int lastMouseX, lastMouseY; 00096 00097 DisplayFunction userDisplayFunction; 00098 KeyboardFunction userKeyboardFunction; 00099 MouseFunction userMouseFunction; 00100 MotionFunction userMotionFunction; 00101 00102 double zoomSensitivity; 00103 double rotateSensitivity; 00104 double moveSensitivity; 00105 double minZoomRange; 00106 double cameraFov; 00107 double minClipRange; 00108 double maxClipRange; 00109 00110 public slots: 00111 void redraw(); 00112 00113 public: 00114 GLWidget(QGLFormat glFormat=QGLFormat(QGL::DoubleBuffer), QWidget *parent = 0); 00115 ~GLWidget(); 00116 00117 QSize minimumSizeHint() const; 00118 QSize sizeHint() const; 00119 00120 void setInitialCameraPos(float pan, float tilt, float range, float xOffset, float yOffset, float zOffset); 00121 00122 void setCameraParams(double zoomSensitivity_, double rotateSensitivity_, double moveSensitivity_, double minZoomRange_, 00123 double cameraFov_, double minClipRange_, double maxClipRange_); 00124 00125 void setDisplayFunction(DisplayFunction func); 00126 void setMouseFunction(MouseFunction func); 00127 void setMotionFunction(MotionFunction func); 00128 00129 void requestRedraw(void); 00130 00131 void recenter(void); 00132 void pickPoint(int mouse_x, int mouse_y, double *scene_x, double *scene_y); 00133 00134 double getCamDistance() {return cameraPose.distance;} 00135 double getCamPan() {return cameraPose.tilt;} 00136 double getCamTilt() {return cameraPose.tilt;} 00137 00138 virtual void mousePressEvent(QMouseEvent *event); 00139 virtual void mouseReleaseEvent(QMouseEvent *event); 00140 virtual void mouseMoveEvent(QMouseEvent *event); 00141 00142 protected: 00143 void rotateCamera(double dx, double dy); 00144 void zoomCamera(double dy); 00145 void moveCamera(double dx, double dy); 00146 void init3DMode(int w, int h, double& fovY, double& zNear, double& zFar); 00147 00148 protected: 00149 virtual void initializeGL(); 00150 virtual void paintGL(); 00151 virtual void resizeGL(int width, int height); 00152 00153 void activate3DMode(); 00154 void activate2DMode(); 00155 00156 protected: 00157 bool refresh_required; 00158 float ambientLight[4]; 00159 float diffuseLight[4]; 00160 float specularLight[4]; 00161 float lightPosition[4]; 00162 bool gl_initialized_; // this flag is set after initializeGL was called..otherwise an early resizeGL might crash the app 00163 00164 private: 00165 static const float ambientLightDefault[4]; 00166 static const float diffuseLightDefault[4]; 00167 static const float specularLightDefault[4]; 00168 static const float lightPositionDefault[4]; 00169 }; 00170 00171 } // namespace vlr 00172 00173 #endif /*GLWIDGET_H*/ 00174 00175