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 #include "renderable.h"
00026
00028 class GLViewer : public QGLWidget {
00029 Q_OBJECT
00030
00031 public:
00032 GLViewer(QWidget *parent = 0);
00033 ~GLViewer();
00034
00035 QSize minimumSizeHint() const;
00036 QSize sizeHint() const;
00037
00038 public Q_SLOTS:
00039 void setXRotation(int angle);
00040 void setYRotation(int angle);
00041 void setZRotation(int angle);
00042 void setStereoShift(double shift);
00043 void setRotationGrid(double rot_step_in_degree);
00044 void toggleFollowMode(bool on);
00045 void toggleShowEdges(bool on);
00046 void toggleShowIDs(bool on);
00047 void toggleShowGrid(bool on);
00048 void toggleShowTFs(bool on);
00049 void toggleShowPoses(bool on);
00050 void toggleShowClouds(bool on);
00051 void toggleShowOctoMap(bool on);
00052 void toggleShowFeatures(bool on);
00053 void toggleBackgroundColor(bool on);
00054 void toggleStereo(bool on);
00055
00056
00057 void addPointCloud(pointcloud_type * pc, QMatrix4x4 transform);
00058 void addFeatures(const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >* feature_locations_3d);
00059 void updateTransforms(QList<QMatrix4x4>* transforms);
00060 void setEdges(const QList<QPair<int, int> >* edge_list);
00061 void deleteLastNode();
00062 void reset();
00063 void toggleTriangulation();
00064 void drawToPS(QString filname);
00065 void setRenderable(Renderable* r);
00066 Q_SIGNALS:
00067 void cloudRendered(pointcloud_type *);
00068 void clickedPosition(float x,float y,float z);
00069
00070
00071
00072
00073 protected:
00074 void initializeGL();
00075 void paintGL();
00076 void resizeGL(int width, int height);
00077 void mousePressEvent(QMouseEvent *event);
00078 void mouseReleaseEvent(QMouseEvent *event);
00079 void mouseMoveEvent(QMouseEvent *event);
00080 void wheelEvent(QWheelEvent *event);
00086 void mouseDoubleClickEvent(QMouseEvent *event);
00088 void drawAxes(float scale, float thickness = 4.0);
00090 void drawEdges();
00092 void drawGrid();
00095 void drawTriangle(const point_type& p1, const point_type& p2, const point_type& p3);
00096
00098 void pointCloud2GLTriangleList(pointcloud_type const * pc);
00100 void pointCloud2GLPoints(pointcloud_type * pc);
00102 void pointCloud2GLStrip(pointcloud_type * pc);
00104 void pointCloud2GLEllipsoids(pointcloud_type * pc);
00105 QImage renderList(QMatrix4x4 transform, int list_id);
00107 void drawOneCloud(int i) ;
00109 void drawClouds(float xshift);
00110 float bg_col_[4];
00112 void makeCurrent();
00113
00114 void initialPosition();
00115 void drawNavigationAxis(int axis_idx, float scale, QString text);
00116 void drawRenderable() ;
00117
00118 private:
00119 void clearAndUpdate();
00120 int xRot, yRot, zRot;
00121 float xTra, yTra, zTra;
00122 QPoint lastPos;
00123 GLenum polygon_mode;
00124 QList<GLuint> cloud_list_indices;
00125 QList<GLuint> feature_list_indices;
00126 QList<QPair<int, int> > edge_list_;
00127 QList<QMatrix4x4>* cloud_matrices;
00128 QMatrix4x4 viewpoint_tf_;
00129
00133 void setViewPoint(QMatrix4x4 cam_pose_mat);
00134 bool setClickedPosition(int x, int y);
00135 bool show_poses_;
00136 bool show_ids_;
00137 bool show_grid_;
00138 bool show_tfs_;
00139 bool show_edges_;
00140 bool show_clouds_;
00141 bool show_octomap_;
00142 bool show_features_;
00143 bool follow_mode_;
00144 bool stereo_;
00145 bool black_background_;
00146 int width_, height_;
00147 double stereo_shift_, fov_;
00148 double rotation_stepping_;
00149 QWidget* myparent;
00150 bool button_pressed_;
00151 bool non_interactive_update_;
00152 unsigned int fast_rendering_step_;
00153 Renderable* external_renderable;
00154 };
00155
00156 void drawEllipsoid(float fA, float fB, float fC, const Eigen::Vector4f& p);
00157 #endif