Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef GLVIEWER_H
00019 #define GLVIEWER_H
00020 #include <QGLWidget>
00021 #include <QList>
00022 #include <QPair>
00023 #include <QMatrix4x4>
00024 #include "parameter_server.h"
00025
00027 class GLViewer : public QGLWidget {
00028 Q_OBJECT
00029
00030 public:
00031 GLViewer(QWidget *parent = 0);
00032 ~GLViewer();
00033
00034 QSize minimumSizeHint() const;
00035 QSize sizeHint() const;
00036
00037 public Q_SLOTS:
00038 void setXRotation(int angle);
00039 void setYRotation(int angle);
00040 void setZRotation(int angle);
00041 void setStereoShift(double shift);
00042 void setRotationGrid(double rot_step_in_degree);
00043 void toggleFollowMode(bool on);
00044 void toggleShowEdges(bool on);
00045 void toggleShowIDs(bool on);
00046 void toggleShowPoses(bool on);
00047 void toggleShowClouds(bool on);
00048 void toggleBackgroundColor(bool on);
00049 void toggleStereo(bool on);
00050
00051
00052 void addPointCloud(pointcloud_type * pc, QMatrix4x4 transform);
00053 void updateTransforms(QList<QMatrix4x4>* transforms);
00054 void setEdges(QList<QPair<int, int> >* edge_list);
00055 void deleteLastNode();
00056 void reset();
00057 void toggleTriangulation();
00058 void drawToPS(QString filname);
00059 Q_SIGNALS:
00060 void cloudRendered(pointcloud_type const *);
00061
00062
00063
00064
00065 protected:
00066 void initializeGL();
00067 void paintGL();
00068 void resizeGL(int width, int height);
00069 void mousePressEvent(QMouseEvent *event);
00070 void mouseMoveEvent(QMouseEvent *event);
00071 void wheelEvent(QWheelEvent *event);
00077 void mouseDoubleClickEvent(QMouseEvent *event);
00079 void drawAxis(float scale);
00081 void drawEdges();
00084 void drawTriangle(const point_type& p1, const point_type& p2, const point_type& p3);
00085
00087 void pointCloud2GLList(pointcloud_type const * pc);
00088 void pointCloud2GLStrip(pointcloud_type * pc);
00089 QImage renderList(QMatrix4x4 transform, int list_id);
00091 void drawClouds(float xshift);
00092
00093 private:
00094 int xRot, yRot, zRot;
00095 float xTra, yTra, zTra;
00096 float bg_col_[4];
00097 QPoint lastPos;
00098 GLenum polygon_mode;
00099 QList<GLuint> cloud_list_indices;
00100 QList<QPair<int, int> >* edge_list_;
00101 QList<QMatrix4x4>* cloud_matrices;
00102 QMatrix4x4 viewpoint_tf_;
00106 void setViewPoint(QMatrix4x4 cam_pose_mat);
00107 bool setClickedPosition(int x, int y);
00108 bool show_poses_;
00109 bool show_ids_;
00110 bool show_edges_;
00111 bool show_clouds_;
00112 bool follow_mode_;
00113 bool stereo_;
00114 int width_, height_;
00115 double stereo_shift_, fov_;
00116 double rotation_stepping_;
00117
00118 };
00119
00120 #endif