StructureGL.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Fraunhofer FKIE
00003  *
00004  * Authors: Bastian Gaspers
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  * * Redistributions of source code must retain the above copyright
00010  *   notice, this list of conditions and the following disclaimer.
00011  * * Redistributions in binary form must reproduce the above copyright
00012  *   notice, this list of conditions and the following disclaimer in the
00013  *   documentation and/or other materials provided with the distribution.
00014  * * Neither the name of the Fraunhofer FKIE nor the names of its
00015  *   contributors may be used to endorse or promote products derived from
00016  *   this software without specific prior written permission.
00017  *
00018  * This file is part of the StructureColoring ROS package.
00019  *
00020  * The StructureColoring ROS package is free software:
00021  * you can redistribute it and/or modify it under the terms of the
00022  * GNU Lesser General Public License as published by the Free
00023  * Software Foundation, either version 3 of the License, or
00024  * (at your option) any later version.
00025  *
00026  * The StructureColoring ROS package is distributed in the hope that it will be useful,
00027  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00028  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00029  * GNU Lesser General Public License for more details.
00030  *
00031  * You should have received a copy of the GNU Lesser General Public License
00032  * along with The StructureColoring ROS package.
00033  * If not, see <http://www.gnu.org/licenses/>.
00034  */
00035 
00036 #ifndef _StructureGL_h_
00037 #define _StructureGL_h_
00038 
00039 #include <QtOpenGL/QGLWidget>
00040 #include <QtCore/QTimer>
00041 #include <QtGui/QKeyEvent>
00042 #include <QtGui/QMouseEvent>
00043 #include <QtGui/QApplication>
00044 #include <QtCore/QMutex>
00045 #include <boost/shared_ptr.hpp>
00046 #include <cmath>
00047 #include <vector>
00048 #include <time.h>
00049 #include <ctime>
00050 #include <opencv/highgui.h>
00051 #include <structureColoring/structures/PlanePatch.h>
00052 #include <structureColoring/structures/CylinderPatch.h>
00053 #include <Eigen/Dense>
00054 #include <Eigen/StdVector>
00055 
00056 class StructureGL: public QGLWidget {
00057 Q_OBJECT
00058 public:
00059         typedef Eigen::Vector3f Vec3;
00060         typedef PlanePatch::PlanePatches PlanePatches;
00061         typedef CylinderPatch::CylinderPatches CylinderPatches;
00062         typedef pcl::PointXYZRGB PointT;
00063         typedef pcl::PointCloud<PointT> PointCloud;
00064         typedef boost::shared_ptr<PointCloud> PointCloudPtr;
00065         typedef GLuint TexID;
00066         typedef std::vector<TexID> TexIDs;
00067 
00073         static void flipToViewport(Vec3& vec, const Vec3& viewport);
00074 
00075         StructureGL(QWidget* parent = 0, const QGLWidget* shareWidget = 0, Qt::WindowFlags f = 0);
00076         StructureGL(QGLContext* context, QWidget* parent = 0, const QGLWidget* shareWidget = 0, Qt::WindowFlags f = 0);
00077         StructureGL(const QGLFormat& format, QWidget* parent = 0, const QGLWidget* shareWidget = 0, Qt::WindowFlags f = 0);
00078 //      ~StructureGL();
00079 
00080         void initializeGL();
00081         void initLight();
00082         void resizeGL(int width, int height);
00083 
00084         void keyPressEvent(QKeyEvent*);
00085         void keyReleaseEvent(QKeyEvent*);
00086         void wheelEvent(QWheelEvent*);
00087         void mouseMoveEvent(QMouseEvent*);
00088         void mousePressEvent(QMouseEvent*);
00089         void mouseReleaseEvent(QMouseEvent*);
00090         void setPerspective(double fovy, double aspekt, double zNear, double zFar);
00091 
00092         void paintGL();
00093         void paintCoordinateSystemGL();
00094         void paintPointsGL();
00095         void paintUnsegPointsGL();
00096         void paintPlanes();
00097         void paintBMPlanes();
00098         void paintHeightMapPlanes();
00099         void paintCylinders();
00100 
00101         void setPointCloud(PointCloudPtr pc){
00102                 if (mPointCloudMutex.tryLock(100)){
00103                         mPointCloud = pc;
00104                         mPointCloudMutex.unlock();
00105                 }
00106         }
00107 
00108         void setUnsegmentedPointCloud(PointCloudPtr pc){
00109                 if (mPointCloudMutex.tryLock(100)){
00110                         mUnsegPointCloud = pc;
00111                         mPointCloudMutex.unlock();
00112                 }
00113         }
00114 
00115         void setPlanePatches(const PlanePatches& pp){
00116                 if (mPlanePatchesMutex.tryLock(100)){
00117                         mPlanePatches = pp;
00118                         resetAllPlaneTextures();
00119                         mPlaneTextureIDs.reserve(pp.size());
00120                         mPlaneAlphaIDs.reserve(pp.size());
00121                         mHeightMapIDs.reserve(pp.size());
00122                         mNormalMapIDs.reserve(pp.size());
00123                         mPlanePatchesMutex.unlock();
00124                         update();
00125                 }
00126         }
00127 
00128         void setCylinderPatches(const CylinderPatches& cp){
00129                 if (mCylinderPatchesMutex.tryLock(100)){
00130                         mCylinderPatches = cp;
00131                         //TODO Do texture things.
00132                         mCylinderPatchesMutex.unlock();
00133                         update();
00134                 }
00135         }
00136 
00137 private Q_SLOTS:
00138         void moveTimeout();
00139 
00140 private:
00141         typedef std::vector<Vec3, Eigen::aligned_allocator<Vec3> > Points;
00142 
00143         class Viewpoint {
00144         public:
00145                 Viewpoint() :
00146                         mX(0.f), mY(0.f), mZ(0.f), mYaw(0.f), mPitch(0.f), mVelForward(0.f), mVelUp(0.f), mVelSide(0.f), mVelTurn(0.f) {
00147                 }
00148                 void setXYZ(float x, float y, float z) {
00149                         mX = x;
00150                         mY = y;
00151                         mZ = z;
00152                 }
00153                 void setYaw(float yaw) {
00154                         mYaw = yaw;
00155                 }
00156                 void setPitch(float pitch) {
00157                         mPitch = pitch;
00158                 }
00159                 void translate(float forward, float up, float sideways);
00160                 void rotate(float yaw, float pitch);
00161                 void setVelocity(float forwardVel, float upVel, float sidewaysVel, float turnVel) {
00162                         mVelForward = forwardVel;
00163                         mVelSide = sidewaysVel;
00164                         mVelTurn = turnVel;
00165                         mVelUp = upVel;
00166                 }
00167                 void setForwardVelocity(float forwardVel) {
00168                         mVelForward = forwardVel;
00169                 }
00170                 void setSidewaysVelocity(float sidewaysVel) {
00171                         mVelSide = sidewaysVel;
00172                 }
00173                 void setTurnVelocity(float turnVel) {
00174                         mVelTurn = turnVel;
00175                 }
00176                 void setUpVelocity(float upVel) {
00177                         mVelUp = upVel;
00178                 }
00179                 void applyGL();
00180                 void applyVelocity(float dt = 1.f);
00181                 float getYaw() {
00182                         return mYaw;
00183                 }
00184                 float getPitch() {
00185                         return mPitch;
00186                 }
00187                 float getX() {
00188                         return mX;
00189                 }
00190                 float getY() {
00191                         return mY;
00192                 }
00193                 float getZ() {
00194                         return mZ;
00195                 }
00196         private:
00197                 float mX, mY, mZ, mYaw, mPitch;
00198                 float mVelForward, mVelUp, mVelSide, mVelTurn;
00199         };
00200 
00201         static void packTo01(Vec3& vec){
00202                 vec += Vec3(1.f, 1.f, 1.f);
00203                 vec *= 0.5f;
00204         }
00205 
00206         void initialize();
00207         void getColorByIndex(float *rgb, unsigned int index, unsigned int total);
00208         void generateNormalisationCubeMap();
00209         void resetAllPlaneTextures();
00210         void resetTextures(TexIDs& textureIDs);
00211         void removedMarkedTextures();
00212 
00213         double mProjM[16], mModelM[16];
00214         int mViewP[4];
00215         GLfloat mLightPos0[4];
00216 
00217         bool mMouseView;
00218         float mTranslationSpeed, mRotationSpeed;
00219         float mYawStart, mPitchStart;
00220         QPoint mStartPos;
00221         Viewpoint mViewpoint;
00222 
00223         std::clock_t mLastTick;
00224         QTimer mMoveTimer;
00225 
00226         bool mForward, mReverse, mLeft, mRight, mUp, mDown, mTurnLeft, mTurnRight;
00227 
00228 
00229 //      GLUquadricObj *mQuadric;
00230 
00231         PointCloudPtr mPointCloud;
00232         PointCloudPtr mUnsegPointCloud;
00233         QMutex mPointCloudMutex;
00234 
00235         PlanePatches mPlanePatches;
00236         QMutex mPlanePatchesMutex;
00237 
00238         CylinderPatches mCylinderPatches;
00239         QMutex mCylinderPatchesMutex;
00240 
00241         QMutex mPlaneTextureMutex;
00242         TexIDs mPlaneTextureIDs;
00243         TexIDs mPlaneAlphaIDs;
00244         TexIDs mHeightMapIDs;
00245         TexIDs mNormalMapIDs;
00246         TexIDs mTexIDsToRemove;
00247         TexID mNormalisationCubeMap;
00248 
00249         bool mShowPoints;
00250         bool mShowPlanes;
00251         bool mShowCylinders;
00252         bool mLight;
00253         bool mBumpMaps;
00254         bool mHeightMaps;
00255         bool mShowUnsegmentedPoints;
00256 };
00257 
00258 
00259 #endif /*_StructureGL_h_*/


structure_coloring_fkie
Author(s): Bastian Gaspers
autogenerated on Sun Jan 5 2014 11:38:09