ViewerWidget.h
Go to the documentation of this file.
1 /*
2  * This file is part of OctoMap - An Efficient Probabilistic 3D Mapping
3  * Framework Based on Octrees
4  * http://octomap.github.io
5  *
6  * Copyright (c) 2009-2014, K.M. Wurm and A. Hornung, University of Freiburg
7  * All rights reserved. License for the viewer octovis: GNU GPL v2
8  * http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt
9  *
10  *
11  * This program is free software; you can redistribute it and/or modify
12  * it under the terms of the GNU General Public License as published by
13  * the Free Software Foundation; either version 2 of the License, or
14  * (at your option) any later version.
15  *
16  * This program is distributed in the hope that it will be useful, but
17  * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
18  * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
19  * for more details.
20  *
21  * You should have received a copy of the GNU General Public License
22  * along with this program. If not, see http://www.gnu.org/licenses/.
23  */
24 
25 #ifndef VIEWERWIDGET_H_
26 #define VIEWERWIDGET_H_
27 
28 #include "SceneObject.h"
29 #include "SelectionBox.h"
30 #include <octomap/octomap.h>
31 #include <qglviewer.h>
32 
33 namespace octomap{
34 
35 class ViewerWidget : public QGLViewer {
36  Q_OBJECT
37 
38  public:
39 
40  ViewerWidget(QWidget* parent = NULL);
41  void clearAll();
42 
48  void addSceneObject(SceneObject* obj);
49 
56  void removeSceneObject(SceneObject* obj);
57 
58  public slots:
59  void enablePrintoutMode (bool enabled = true);
60  void enableHeightColorMode (bool enabled = true);
61  void enableSemanticColoring (bool enabled = true);
62  void enableSelectionBox (bool enabled = true);
63  void setCamPosition(double x, double y, double z, double lookX, double lookY, double lookZ);
64  void setCamPose(const octomath::Pose6D& pose);
65  virtual void setSceneBoundingBox(const qglviewer::Vec& min, const qglviewer::Vec& max);
66  void deleteCameraPath(int id);
67  void appendToCameraPath(int id, const octomath::Pose6D& pose);
68  void appendCurrentToCameraPath(int id);
69  void addCurrentToCameraPath(int id, int frame);
70  void removeFromCameraPath(int id, int frame);
71  void updateCameraPath(int id, int frame);
72  void jumpToCamFrame(int id, int frame);
73  void playCameraPath(int id, int start_frame);
74  void stopCameraPath(int id);
75  const SelectionBox& selectionBox() const { return m_selectionBox;}
76 
80  void resetView();
81 
82 private slots:
83  void cameraPathFinished();
85 
86 signals:
87  void cameraPathStopped(int id);
88  void cameraPathFrameChanged(int id, int current_camera_frame);
89  void select(const QMouseEvent* e);
90 
91  protected:
92 
93  virtual void draw();
94  virtual void drawWithNames();
95  virtual void init();
99  virtual void postDraw();
100  virtual void postSelection(const QPoint&);
101  virtual QString helpString() const;
102 
104 
105  std::vector<SceneObject*> m_sceneObjects;
107 
111 
112  bool m_drawAxis; // actual state of axis (original overwritten)
113  bool m_drawGrid; // actual state of grid (original overwritten)
115 
116  double m_zMin;
117  double m_zMax;
118 
121 };
122 
123 }
124 
125 #endif /* VIEWERWIDGET_H_ */
SelectionBox.h
octomap::ViewerWidget::m_zMin
double m_zMin
Definition: ViewerWidget.h:116
octomap::ViewerWidget::deleteCameraPath
void deleteCameraPath(int id)
Definition: ViewerWidget.cpp:166
octomap::ViewerWidget::setCamPosition
void setCamPosition(double x, double y, double z, double lookX, double lookY, double lookZ)
Definition: ViewerWidget.cpp:142
octomap::ViewerWidget::select
void select(const QMouseEvent *e)
octomap::ViewerWidget::updateCameraPath
void updateCameraPath(int id, int frame)
Definition: ViewerWidget.cpp:199
octomap::ViewerWidget::postDraw
virtual void postDraw()
Definition: ViewerWidget.cpp:354
octomap::ViewerWidget::appendToCameraPath
void appendToCameraPath(int id, const octomath::Pose6D &pose)
Definition: ViewerWidget.cpp:175
octomap::ViewerWidget::poseToQGLQuaternion
qglviewer::Quaternion poseToQGLQuaternion(const octomath::Pose6D &pose)
Definition: ViewerWidget.cpp:125
octomap::ViewerWidget::playCameraPath
void playCameraPath(int id, int start_frame)
Definition: ViewerWidget.cpp:238
octomap::ViewerWidget::stopCameraPath
void stopCameraPath(int id)
Definition: ViewerWidget.cpp:252
qglviewer::Quaternion
The Quaternion class represents 3D rotations and orientations.
Definition: quaternion.h:86
octomap::ViewerWidget::m_heightColorMode
bool m_heightColorMode
Definition: ViewerWidget.h:109
octomap::ViewerWidget
Definition: ViewerWidget.h:35
octomap::ViewerWidget::init
virtual void init()
Definition: ViewerWidget.cpp:45
octomap::ViewerWidget::draw
virtual void draw()
Definition: ViewerWidget.cpp:316
octomap::SceneObject
Definition: SceneObject.h:48
octomap::ViewerWidget::m_current_camera_path
int m_current_camera_path
Definition: ViewerWidget.h:119
octomap::ViewerWidget::m_drawGrid
bool m_drawGrid
Definition: ViewerWidget.h:113
qglviewer::Vec
The Vec class represents 3D positions and 3D vectors.
Definition: vec.h:85
octomap::ViewerWidget::setCamPose
void setCamPose(const octomath::Pose6D &pose)
Definition: ViewerWidget.cpp:150
octomap::ViewerWidget::m_semantic_coloring
bool m_semantic_coloring
Definition: ViewerWidget.h:110
octomap::ViewerWidget::cameraPathStopped
void cameraPathStopped(int id)
octomap::ViewerWidget::enableHeightColorMode
void enableHeightColorMode(bool enabled=true)
Definition: ViewerWidget.cpp:95
octomap::ViewerWidget::removeSceneObject
void removeSceneObject(SceneObject *obj)
Definition: ViewerWidget.cpp:297
octomap::ViewerWidget::helpString
virtual QString helpString() const
Definition: ViewerWidget.cpp:79
octomap::ViewerWidget::m_selectionBox
SelectionBox m_selectionBox
Definition: ViewerWidget.h:106
octomap::ViewerWidget::enableSemanticColoring
void enableSemanticColoring(bool enabled=true)
Definition: ViewerWidget.cpp:111
QGLViewer
A versatile 3D OpenGL viewer based on QGLWidget.
Definition: qglviewer.h:62
octomap::ViewerWidget::cameraPathInterpolated
void cameraPathInterpolated()
Definition: ViewerWidget.cpp:270
octomap::ViewerWidget::m_sceneObjects
std::vector< SceneObject * > m_sceneObjects
Definition: ViewerWidget.h:105
octomap::ViewerWidget::resetView
void resetView()
Definition: ViewerWidget.cpp:72
octomap::ViewerWidget::drawWithNames
virtual void drawWithNames()
Definition: ViewerWidget.cpp:348
octomap::ViewerWidget::enablePrintoutMode
void enablePrintoutMode(bool enabled=true)
Definition: ViewerWidget.cpp:103
octomap::ViewerWidget::addSceneObject
void addSceneObject(SceneObject *obj)
Definition: ViewerWidget.cpp:291
octomap::ViewerWidget::ViewerWidget
ViewerWidget(QWidget *parent=NULL)
Definition: ViewerWidget.cpp:36
SceneObject.h
octomap::ViewerWidget::cameraPathFinished
void cameraPathFinished()
Definition: ViewerWidget.cpp:261
octomap::ViewerWidget::setSceneBoundingBox
virtual void setSceneBoundingBox(const qglviewer::Vec &min, const qglviewer::Vec &max)
Definition: ViewerWidget.cpp:285
octomap::ViewerWidget::clearAll
void clearAll()
Definition: ViewerWidget.cpp:309
qglviewer.h
octomap::ViewerWidget::m_drawSelectionBox
bool m_drawSelectionBox
Definition: ViewerWidget.h:114
octomap::ViewerWidget::cameraPathFrameChanged
void cameraPathFrameChanged(int id, int current_camera_frame)
octomap::ViewerWidget::addCurrentToCameraPath
void addCurrentToCameraPath(int id, int frame)
Definition: ViewerWidget.cpp:221
octomap::ViewerWidget::m_current_camera_frame
int m_current_camera_frame
Definition: ViewerWidget.h:120
octomap.h
octomap::ViewerWidget::m_printoutMode
bool m_printoutMode
Definition: ViewerWidget.h:108
octomap
octomath::Pose6D
octomap::ViewerWidget::m_drawAxis
bool m_drawAxis
Definition: ViewerWidget.h:112
octomap::ViewerWidget::m_zMax
double m_zMax
Definition: ViewerWidget.h:117
octomap::ViewerWidget::appendCurrentToCameraPath
void appendCurrentToCameraPath(int id)
Definition: ViewerWidget.cpp:215
octomap::ViewerWidget::removeFromCameraPath
void removeFromCameraPath(int id, int frame)
Definition: ViewerWidget.cpp:185
octomap::SelectionBox
Definition: SelectionBox.h:31
octomap::ViewerWidget::postSelection
virtual void postSelection(const QPoint &)
Definition: ViewerWidget.cpp:390
octomap::ViewerWidget::selectionBox
const SelectionBox & selectionBox() const
Definition: ViewerWidget.h:75
octomap::ViewerWidget::jumpToCamFrame
void jumpToCamFrame(int id, int frame)
Definition: ViewerWidget.cpp:155
octomap::ViewerWidget::enableSelectionBox
void enableSelectionBox(bool enabled=true)
Definition: ViewerWidget.cpp:119


octovis
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Apr 3 2025 02:40:44