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
00019
00020
00021
00022
00023
00024
00025 #ifndef VIEWERWIDGET_H_
00026 #define VIEWERWIDGET_H_
00027
00028 #include "SceneObject.h"
00029 #include "SelectionBox.h"
00030 #include <octomap/octomap.h>
00031 #include <qglviewer.h>
00032
00033 namespace octomap{
00034
00035 class ViewerWidget : public QGLViewer {
00036 Q_OBJECT
00037
00038 public:
00039
00040 ViewerWidget(QWidget* parent = NULL);
00041 void clearAll();
00042
00048 void addSceneObject(SceneObject* obj);
00049
00056 void removeSceneObject(SceneObject* obj);
00057
00058 public slots:
00059 void enablePrintoutMode (bool enabled = true);
00060 void enableHeightColorMode (bool enabled = true);
00061 void enableSemanticColoring (bool enabled = true);
00062 void enableSelectionBox (bool enabled = true);
00063 void setCamPosition(double x, double y, double z, double lookX, double lookY, double lookZ);
00064 void setCamPose(const octomath::Pose6D& pose);
00065 virtual void setSceneBoundingBox(const qglviewer::Vec& min, const qglviewer::Vec& max);
00066 void deleteCameraPath(int id);
00067 void appendToCameraPath(int id, const octomath::Pose6D& pose);
00068 void appendCurrentToCameraPath(int id);
00069 void addCurrentToCameraPath(int id, int frame);
00070 void removeFromCameraPath(int id, int frame);
00071 void updateCameraPath(int id, int frame);
00072 void jumpToCamFrame(int id, int frame);
00073 void playCameraPath(int id, int start_frame);
00074 void stopCameraPath(int id);
00075 const SelectionBox& selectionBox() const { return m_selectionBox;}
00076
00080 void resetView();
00081
00082 private slots:
00083 void cameraPathFinished();
00084 void cameraPathInterpolated();
00085
00086 signals:
00087 void cameraPathStopped(int id);
00088 void cameraPathFrameChanged(int id, int current_camera_frame);
00089
00090 protected:
00091
00092 virtual void draw();
00093 virtual void drawWithNames();
00094 virtual void init();
00098 virtual void postDraw();
00099 virtual void postSelection(const QPoint&);
00100 virtual QString helpString() const;
00101
00102 qglviewer::Quaternion poseToQGLQuaternion(const octomath::Pose6D& pose);
00103
00104 std::vector<SceneObject*> m_sceneObjects;
00105 SelectionBox m_selectionBox;
00106
00107 bool m_printoutMode;
00108 bool m_heightColorMode;
00109 bool m_semantic_coloring;
00110
00111 bool m_drawAxis;
00112 bool m_drawGrid;
00113 bool m_drawSelectionBox;
00114
00115 double m_zMin;
00116 double m_zMax;
00117
00118 int m_current_camera_path;
00119 int m_current_camera_frame;
00120 };
00121
00122 }
00123
00124 #endif