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