Project

General

Profile

Statistics
| Branch: | Revision:

root / rgbdslam / src / glviewer.h @ 9240aaa3

History | View | Annotate | Download (3.42 KB)

1
/* This file is part of RGBDSLAM.
2
 * 
3
 * RGBDSLAM is free software: you can redistribute it and/or modify
4
 * it under the terms of the GNU General Public License as published by
5
 * the Free Software Foundation, either version 3 of the License, or
6
 * (at your option) any later version.
7
 * 
8
 * RGBDSLAM is distributed in the hope that it will be useful,
9
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
10
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
11
 * GNU General Public License for more details.
12
 * 
13
 * You should have received a copy of the GNU General Public License
14
 * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
15
 */
16

    
17

    
18
#ifndef GLVIEWER_H
19
#define GLVIEWER_H
20
#include <QGLWidget>
21
#include <QList>
22
#include <QPair>
23
#include <QMatrix4x4>
24
#include "parameter_server.h"
25

    
26
//!OpenGL based display of the 3d model 
27
class GLViewer : public QGLWidget {
28
    Q_OBJECT
29

    
30
public:
31
    GLViewer(QWidget *parent = 0);
32
    ~GLViewer();
33

    
34
    QSize minimumSizeHint() const;
35
    QSize sizeHint() const;
36
    void addPointCloud(pointcloud_type * pc, QMatrix4x4 transform);
37
    void deleteLastNode();
38
    void updateTransforms(QList<QMatrix4x4>* transforms);
39
    void setEdges(QList<QPair<int, int> >* edge_list);
40
    void reset();
41
    void toggleTriangulation();
42

    
43
public Q_SLOTS:
44
    void setXRotation(int angle);
45
    void setYRotation(int angle);
46
    void setZRotation(int angle);
47
    void toggleFollowMode(bool on);
48
    void toggleShowAxis(bool on);
49

    
50
Q_SIGNALS:
51
    void cloudRendered(pointcloud_type const *);
52
    //void xRotationChanged(int angle);
53
    //void yRotationChanged(int angle);
54
    //void zRotationChanged(int angle);
55

    
56
protected:
57
    void initializeGL();
58
    void paintGL();
59
    void resizeGL(int width, int height);
60
    void mousePressEvent(QMouseEvent *event);
61
    void mouseMoveEvent(QMouseEvent *event);
62
    void wheelEvent(QWheelEvent *event);
63
    //!Resets to certain perspectives
64
    ///Double clicks onto an object part will make that part the pivot of 
65
    ///The camera movement. Depending on the button the position of the camera
66
    ///will be the most recent frame (left button) or the first frame (right button).
67
    ///If the background is clicked, the pivot will be the camera position itself
68
    void mouseDoubleClickEvent(QMouseEvent *event);
69
    ///Draw colored axis, scale long
70
    void drawAxis(float scale);
71
    void drawEdges();
72
    ///Draw coil. For debugging only
73
    void drawCoil();
74
    /**Defines a triangle for opengl */
75
    bool drawTriangle(const point_type& p1, const point_type& p2, 
76
                      const point_type& p3);
77
    //bool startTriangleStrip(pointcloud_type const * pc, int x, int y, int w, int h, bool& flip);
78
    ///Compile the pointcloud to a GL Display List
79
    void pointCloud2GLList(pointcloud_type const * pc);
80
    void pointCloud2GLStrip(pointcloud_type * pc);
81
    QImage renderList(QMatrix4x4 transform, int list_id);
82

    
83
private:
84
    int xRot, yRot, zRot;
85
    float xTra, yTra, zTra;
86
    QPoint lastPos;
87
    GLenum polygon_mode;
88
    QList<GLuint> cloud_list_indices;
89
    QList<QPair<int, int> >* edge_list_;
90
    QList<QMatrix4x4>* cloud_matrices;
91
    QMatrix4x4 viewpoint_tf_;
92
    //!cam_pose_mat transforms the viewpoint from the origin
93
    ///cam_pose_mat is inverted, i.e. it should describes the transformation
94
    ///of the camera itself
95
    void setViewPoint(QMatrix4x4 cam_pose_mat);
96
    void setClickedPosition(int x, int y);
97
    bool show_axis_;
98
    bool follow_mode_;
99

    
100
};
101

    
102
#endif