ViewerWidget.cpp
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 #include <octovis/ViewerWidget.h>
26 #include <manipulatedCameraFrame.h>
27 
28 #ifndef M_PI_2
29 #define M_PI_2 1.5707963267948966192E0
30 #endif
31 
32 using namespace std;
33 
34 namespace octomap {
35 
36 ViewerWidget::ViewerWidget(QWidget* parent) :
37  QGLViewer(parent), m_zMin(0.0),m_zMax(1.0) {
38 
39  m_printoutMode = false;
40  m_heightColorMode = false;
41  m_semantic_coloring = false;
42  m_drawSelectionBox = false;
43 }
44 
46 
47  // setHandlerKeyboardModifiers(QGLViewer::CAMERA, Qt::AltModifier);
48  // setHandlerKeyboardModifiers(QGLViewer::FRAME, Qt::NoModifier);
49  // setHandlerKeyboardModifiers(QGLViewer::CAMERA, Qt::ControlModifier);
50  setMouseTracking(true);
51 
52  // Restore previous viewer state.
54 
55  // Make camera the default manipulated frame.
56  setManipulatedFrame( camera()->frame() );
57  // invert mousewheel (more like Blender)
58  camera()->frame()->setWheelSensitivity(-1.0);
59 
60 
61  // Light initialization:
62  glEnable(GL_LIGHT0);
63 
64  float pos[4] = {-1.0, 1.0, 1.0, 0.0};
65  // Directional light
66  glLightfv(GL_LIGHT0, GL_POSITION, pos);
67 
68  // background color defaults to white
69  this->setBackgroundColor( QColor(255,255,255) );
70 }
71 
73  this->camera()->setOrientation((float) -M_PI_2, (float) M_PI_2);
74  this->showEntireScene();
75  update();
76 }
77 
78 
79 QString ViewerWidget::helpString() const{
80  QString help = "<h2>Octomap 3D viewer</h2>";
81 
82  help +="The Octomap library implements a 3D occupancy grid mapping approach. "
83  "It provides data structures and mapping algorithms. The map is implemented "
84  "using an octree. 3D maps can be viewed an built using this 3D viewer."
85  "<br/><br/>"
86  "Octomap is available at https://octomap.github.io, and is actively "
87  "maintained by Kai M. Wurm and Armin Hornung. This 3D viewer is based on "
88  "libQGLViewer, available at http://www.libqglviewer.com/."
89  "<br/><br/>"
90  "Please refer to the \"Keyboard\" and \"Mouse\" tabs for instructions on "
91  "how to use the viewer.";
92  return help;
93 }
94 
96  m_heightColorMode = enabled;
97  for(std::vector<SceneObject*>::iterator it = m_sceneObjects.begin(); it != m_sceneObjects.end(); it++) {
98  (*it)->enableHeightColorMode(enabled);
99  }
100  update();
101 }
102 
104  m_printoutMode = enabled;
105  for(std::vector<SceneObject*>::iterator it = m_sceneObjects.begin(); it != m_sceneObjects.end(); it++) {
106  (*it)->enablePrintoutMode(enabled);
107  }
108  update();
109 }
110 
112  m_semantic_coloring = enabled;
113  for(std::vector<SceneObject*>::iterator it = m_sceneObjects.begin(); it != m_sceneObjects.end(); it++) {
114  (*it)->enableSemanticColoring(enabled);
115  }
116  update();
117 }
118 
120  m_drawSelectionBox = enabled;
121  update();
122 }
123 
124 
126  // copying octomap::Quaternion parameters to qglviewer::Quaternion does not work (reason unknown)
127  // octomath::Quaternion quaternion = pose.rot().normalized();
128  // return qglviewer::Quaternion(quaternion.x(), quaternion.y(), quaternion.z(), quaternion.u());
129 
130  // Compute viewing direction and use code from libqglviewer's "look at" function
131  octomath::Vector3 dir = pose.rot().rotate(octomath::Vector3(1.,0.,0.));
132  qglviewer::Vec direction(dir.x(), dir.y(), dir.z());
133  //qglviewer::Vec xAxis = direction ^ camera()->upVector();
134  // useing 0, 0, 1 as upvector instead:
135  qglviewer::Vec xAxis = direction ^ qglviewer::Vec(0.0, 0.0, 1.0);
136 
138  q.setFromRotatedBasis(xAxis, xAxis^direction, -direction);
139  return q;
140 }
141 
142 void ViewerWidget::setCamPosition(double x, double y, double z, double lookX, double lookY, double lookZ){
143  this->camera()->setOrientation(-M_PI/2., M_PI/2.);
144  camera()->setPosition(qglviewer::Vec(x, y, z));
145  camera()->lookAt(qglviewer::Vec(lookX, lookY, lookZ));
146  camera()->setUpVector(qglviewer::Vec(0.0, 0.0, 1.0));
147  update();
148 }
149 
152  setCamPosition(pose.x(), pose.y(), pose.z(), ahead.x(), ahead.y(), ahead.z());
153 }
154 
155 void ViewerWidget::jumpToCamFrame(int id, int frame) {
157  if(kfi && frame >= 0 && frame < kfi->numberOfKeyFrames()) {
158  camera()->setPosition(kfi->keyFrame(frame).position());
159  camera()->setOrientation(kfi->keyFrame(frame).orientation());
160  } else {
161  std::cerr << "Error: Could not jump to frame " << frame << " of " << kfi->numberOfKeyFrames() << std::endl;
162  }
163  update();
164 }
165 
167  if(camera()->keyFrameInterpolator(id)) {
168  disconnect(camera()->keyFrameInterpolator(id), SIGNAL(interpolated()), this, SLOT(update()));
169  disconnect(camera()->keyFrameInterpolator(id), SIGNAL(interpolated()), this, SLOT(cameraPathInterpolated()));
170  disconnect(camera()->keyFrameInterpolator(id), SIGNAL(endReached()), this, SLOT(cameraPathFinished()));
171  camera()->deletePath(id);
172  }
173 }
174 
176  qglviewer::Vec position(pose.trans().x(), pose.trans().y(), pose.trans().z());
177  qglviewer::Quaternion quaternion = poseToQGLQuaternion(pose);
178  qglviewer::Frame frame(position, quaternion);
179  if(!camera()->keyFrameInterpolator(id)) {
181  }
182  camera()->keyFrameInterpolator(id)->addKeyFrame(frame);
183 }
184 
185 void ViewerWidget::removeFromCameraPath(int id, int frame) {
187  if(old_kfi) {
189  for(int i = 0; i < old_kfi->numberOfKeyFrames(); i++) {
190  if(i != frame) {
191  new_kfi->addKeyFrame(old_kfi->keyFrame(i));
192  }
193  }
194  deleteCameraPath(id);
195  camera()->setKeyFrameInterpolator(id, new_kfi);
196  }
197 }
198 
199 void ViewerWidget::updateCameraPath(int id, int frame) {
201  if(old_kfi) {
203  for(int i = 0; i < old_kfi->numberOfKeyFrames(); i++) {
204  if(i != frame) {
205  new_kfi->addKeyFrame(old_kfi->keyFrame(i));
206  } else {
207  new_kfi->addKeyFrame(*(camera()->frame()));
208  }
209  }
210  deleteCameraPath(id);
211  camera()->setKeyFrameInterpolator(id, new_kfi);
212  }
213 }
214 
216  int frame = 0;
217  if(camera()->keyFrameInterpolator(id)) frame = camera()->keyFrameInterpolator(id)->numberOfKeyFrames();
218  addCurrentToCameraPath(id, frame);
219 }
220 
221 void ViewerWidget::addCurrentToCameraPath(int id, int frame) {
223  if(!old_kfi || frame >= old_kfi->numberOfKeyFrames()) {
224  camera()->addKeyFrameToPath(id);
225  } else {
227  for(int i = 0; i < old_kfi->numberOfKeyFrames(); i++) {
228  new_kfi->addKeyFrame(old_kfi->keyFrame(i));
229  if(i == frame) {
230  new_kfi->addKeyFrame(camera()->frame());
231  }
232  }
233  deleteCameraPath(id);
234  camera()->setKeyFrameInterpolator(id, new_kfi);
235  }
236 }
237 
238 void ViewerWidget::playCameraPath(int id, int start_frame) {
240  if(kfi && !kfi->interpolationIsStarted() && start_frame >= 0 && start_frame < kfi->numberOfKeyFrames()) {
242  m_current_camera_frame = start_frame;
243  kfi->setInterpolationTime(kfi->keyFrameTime(start_frame));
244  std::cout << "Playing path of length " << kfi->numberOfKeyFrames() << ", start time " << kfi->keyFrameTime(start_frame) << std::endl;
245  connect(kfi, SIGNAL(interpolated()), this, SLOT(update()));
246  connect(kfi, SIGNAL(interpolated()), this, SLOT(cameraPathInterpolated()));
247  connect(kfi, SIGNAL(endReached()), this, SLOT(cameraPathFinished()));
248  kfi->startInterpolation();
249  }
250 }
251 
253  if(camera()->keyFrameInterpolator(id) && camera()->keyFrameInterpolator(id)->interpolationIsStarted()) {
254  disconnect(camera()->keyFrameInterpolator(id), SIGNAL(interpolated()), this, SLOT(update()));
255  disconnect(camera()->keyFrameInterpolator(id), SIGNAL(interpolated()), this, SLOT(cameraPathInterpolated()));
256  disconnect(camera()->keyFrameInterpolator(id), SIGNAL(endReached()), this, SLOT(cameraPathFinished()));
258  }
259 }
260 
262  if(camera()->keyFrameInterpolator(m_current_camera_path)) {
263  disconnect(camera()->keyFrameInterpolator(m_current_camera_path), SIGNAL(interpolated()), this, SLOT(update()));
264  disconnect(camera()->keyFrameInterpolator(m_current_camera_path), SIGNAL(interpolated()), this, SLOT(cameraPathInterpolated()));
265  disconnect(camera()->keyFrameInterpolator(m_current_camera_path), SIGNAL(endReached()), this, SLOT(cameraPathFinished()));
267  }
268 }
269 
272  if(kfi) {
273  int current_frame = m_current_camera_frame;
274  for(int i = m_current_camera_frame + 1; i < kfi->numberOfKeyFrames(); i++) {
275  if(kfi->keyFrameTime(current_frame) <= kfi->interpolationTime()) current_frame = i;
276  else break;
277  }
278  if(current_frame != m_current_camera_frame) {
279  m_current_camera_frame = current_frame;
281  }
282  }
283 }
284 
286  m_zMin = min[2];
287  m_zMax = max[2];
289 }
290 
292  assert (obj);
293  m_sceneObjects.push_back(obj);
294  update();
295 }
296 
298  assert(obj);
299  for(std::vector<SceneObject*>::iterator it = m_sceneObjects.begin();
300  it != m_sceneObjects.end();){
301  if (*it == obj)
302  it = m_sceneObjects.erase(it);
303  else
304  ++it;
305  }
306  update();
307 }
308 
310  // clear drawable objects:
311  for(std::vector<SceneObject*>::iterator it = m_sceneObjects.begin(); it != m_sceneObjects.end(); it++){
312  (*it)->clear();
313  }
314 }
315 
317 
318  // debugging: draw light in scene
319  //drawLight(GL_LIGHT0);
320 
321  glEnable(GL_BLEND);
322  glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
323 
324  glEnable(GL_LIGHTING);
325  if (m_printoutMode){
326  glCullFace(GL_BACK);
327  }
328 
329  // draw drawable objects:
330  for(std::vector<SceneObject*>::iterator it = m_sceneObjects.begin();
331  it != m_sceneObjects.end(); ++it){
332  (*it)->draw();
333  }
334 
335  if (m_drawSelectionBox){
337 
338  if (m_selectionBox.getGrabbedFrame() >= 0){
339  setMouseBinding(Qt::LeftButton, FRAME, TRANSLATE);
340  } else {
341  setMouseBinding(Qt::LeftButton, FRAME, ROTATE);
342  }
343 
344  }
345 
346 }
347 
349 
350  if (m_drawSelectionBox)
351  m_selectionBox.draw(true);
352 }
353 
355 
356  // Reset model view matrix to world coordinates origin
357  glMatrixMode(GL_MODELVIEW);
358  glPushMatrix();
360  // TODO restore model loadProjectionMatrixStereo
361 
362  // Save OpenGL state
363  glPushAttrib(GL_ALL_ATTRIB_BITS);
364 
365  glDisable(GL_COLOR_MATERIAL);
366 
367  if (gridIsDrawn()){
368  glLineWidth(1.0);
369  drawGrid(5.0, 10);
370  }
371  if (axisIsDrawn()){
372  glLineWidth(2.0);
373  drawAxis(1.0);
374  }
375 
376  // Restore GL state
377  glPopAttrib();
378  glPopMatrix();
379 
382  setAxisIsDrawn(false);
383  setGridIsDrawn(false);
385 
388 }
389 
390 void ViewerWidget::postSelection(const QPoint&)
391 {
392 
393 }
394 
395 
396 
397 } // namespace
398 
octomath::Pose6D::x
float & x()
octomap::ViewerWidget::m_zMin
double m_zMin
Definition: ViewerWidget.h:116
QGLViewer::setManipulatedFrame
void setManipulatedFrame(qglviewer::ManipulatedFrame *frame)
Definition: qglviewer.cpp:3057
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
QGLViewer::drawGrid
static void drawGrid(qreal size=1.0, int nbSubdivisions=10)
Definition: qglviewer.cpp:3323
octomap::ViewerWidget::updateCameraPath
void updateCameraPath(int id, int frame)
Definition: ViewerWidget.cpp:199
QGLViewer::showEntireScene
void showEntireScene()
Definition: qglviewer.h:242
octomap::ViewerWidget::postDraw
virtual void postDraw()
Definition: ViewerWidget.cpp:354
qglviewer::Frame::position
Vec position() const
Definition: frame.cpp:537
octomap::ViewerWidget::appendToCameraPath
void appendToCameraPath(int id, const octomath::Pose6D &pose)
Definition: ViewerWidget.cpp:175
qglviewer::KeyFrameInterpolator::addKeyFrame
void addKeyFrame(const Frame &frame)
Definition: keyFrameInterpolator.cpp:236
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
qglviewer::Camera::loadModelViewMatrix
virtual void loadModelViewMatrix(bool reset=true) const
Definition: camera.cpp:500
octomap::SelectionBox::draw
void draw(bool withNames=false)
Definition: SelectionBox.cpp:77
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
qglviewer::Camera::setOrientation
void setOrientation(const Quaternion &q)
Definition: camera.cpp:1150
M_PI_2
#define M_PI_2
Definition: ViewerWidget.cpp:29
octomath::Pose6D::z
float & z()
QGLViewer::axisIsDrawn
bool axisIsDrawn() const
Definition: qglviewer.h:97
manipulatedCameraFrame.h
QGLViewer::help
virtual void help()
Definition: qglviewer.cpp:1975
QGLViewer::restoreStateFromFile
virtual bool restoreStateFromFile()
Definition: qglviewer.cpp:3460
octomap::SelectionBox::getGrabbedFrame
int getGrabbedFrame() const
Definition: SelectionBox.cpp:229
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
qglviewer::KeyFrameInterpolator::numberOfKeyFrames
int numberOfKeyFrames() const
Definition: keyFrameInterpolator.h:212
qglviewer::ManipulatedFrame::setWheelSensitivity
void setWheelSensitivity(qreal sensitivity)
Definition: manipulatedFrame.h:168
qglviewer::KeyFrameInterpolator::interpolationIsStarted
bool interpolationIsStarted() const
Definition: keyFrameInterpolator.h:286
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
octomath::Pose6D::y
float & y()
octomath::Vector3
octomap::ViewerWidget::helpString
virtual QString helpString() const
Definition: ViewerWidget.cpp:79
octomap::ViewerWidget::m_selectionBox
SelectionBox m_selectionBox
Definition: ViewerWidget.h:106
qglviewer::Camera::deletePath
virtual void deletePath(unsigned int i)
Definition: camera.cpp:1762
octomath::Quaternion::rotate
Vector3 rotate(const Vector3 &v) const
qglviewer::Camera::keyFrameInterpolator
KeyFrameInterpolator * keyFrameInterpolator(unsigned int i) const
Definition: camera.cpp:1664
qglviewer::Camera::setKeyFrameInterpolator
void setKeyFrameInterpolator(unsigned int i, KeyFrameInterpolator *const kfi)
Definition: camera.cpp:1690
QGLViewer::TRANSLATE
@ TRANSLATE
Definition: qglviewer.h:970
octomap::ViewerWidget::enableSemanticColoring
void enableSemanticColoring(bool enabled=true)
Definition: ViewerWidget.cpp:111
QGLViewer::ROTATE
@ ROTATE
Definition: qglviewer.h:970
qglviewer::Camera::addKeyFrameToPath
virtual void addKeyFrameToPath(unsigned int i)
Definition: camera.cpp:1710
QGLViewer::setAxisIsDrawn
void setAxisIsDrawn(bool draw=true)
Definition: qglviewer.h:128
QGLViewer
A versatile 3D OpenGL viewer based on QGLWidget.
Definition: qglviewer.h:62
octomap::ViewerWidget::cameraPathInterpolated
void cameraPathInterpolated()
Definition: ViewerWidget.cpp:270
QGLViewer::postDraw
virtual void postDraw()
Definition: qglviewer.cpp:339
qglviewer::KeyFrameInterpolator::startInterpolation
void startInterpolation(int period=-1)
Definition: keyFrameInterpolator.cpp:126
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
qglviewer::KeyFrameInterpolator::keyFrameTime
qreal keyFrameTime(int index) const
Definition: keyFrameInterpolator.cpp:468
octomap::ViewerWidget::addSceneObject
void addSceneObject(SceneObject *obj)
Definition: ViewerWidget.cpp:291
qglviewer::KeyFrameInterpolator::interpolationTime
qreal interpolationTime() const
Definition: keyFrameInterpolator.h:225
ViewerWidget.h
octomap::ViewerWidget::cameraPathFinished
void cameraPathFinished()
Definition: ViewerWidget.cpp:261
qglviewer::Quaternion::setFromRotatedBasis
void setFromRotatedBasis(const Vec &X, const Vec &Y, const Vec &Z)
Definition: quaternion.cpp:182
octomap::ViewerWidget::setSceneBoundingBox
virtual void setSceneBoundingBox(const qglviewer::Vec &min, const qglviewer::Vec &max)
Definition: ViewerWidget.cpp:285
qglviewer::Frame
The Frame class represents a coordinate system, defined by a position and an orientation.
Definition: frame.h:141
qglviewer::Camera::setUpVector
void setUpVector(const Vec &up, bool noMove=true)
Definition: camera.cpp:1116
octomap::ViewerWidget::clearAll
void clearAll()
Definition: ViewerWidget.cpp:309
octomap::ViewerWidget::m_drawSelectionBox
bool m_drawSelectionBox
Definition: ViewerWidget.h:114
QGLViewer::drawAxis
static void drawAxis(qreal length=1.0)
Definition: qglviewer.cpp:3255
octomap::ViewerWidget::cameraPathFrameChanged
void cameraPathFrameChanged(int id, int current_camera_frame)
octomath::Vector3::y
float & y()
octomap::ViewerWidget::addCurrentToCameraPath
void addCurrentToCameraPath(int id, int frame)
Definition: ViewerWidget.cpp:221
qglviewer::Camera::frame
ManipulatedCameraFrame * frame() const
Definition: camera.h:334
QGLViewer::setMouseBinding
void setMouseBinding(unsigned int state, MouseHandler handler, MouseAction action, bool withConstraint=true)
Definition: qglviewer.cpp:2512
octomath::Pose6D::rot
Quaternion & rot()
M_PI
#define M_PI
octomap::ViewerWidget::m_current_camera_frame
int m_current_camera_frame
Definition: ViewerWidget.h:120
QGLViewer::setSceneBoundingBox
void setSceneBoundingBox(const qglviewer::Vec &min, const qglviewer::Vec &max)
Definition: qglviewer.h:237
QGLViewer::setBackgroundColor
void setBackgroundColor(const QColor &color)
Definition: qglviewer.h:186
qglviewer::KeyFrameInterpolator::setInterpolationTime
void setInterpolationTime(qreal time)
Definition: keyFrameInterpolator.h:267
octomap::ViewerWidget::m_printoutMode
bool m_printoutMode
Definition: ViewerWidget.h:108
octomap
qglviewer::Camera::lookAt
void lookAt(const Vec &target)
Definition: camera.cpp:1008
octomath::Pose6D
qglviewer::KeyFrameInterpolator::keyFrame
Frame keyFrame(int index) const
Definition: keyFrameInterpolator.cpp:459
octomap::ViewerWidget::m_drawAxis
bool m_drawAxis
Definition: ViewerWidget.h:112
qglviewer::Camera::setPosition
void setPosition(const Vec &pos)
Definition: camera.cpp:1240
QGLViewer::setGridIsDrawn
void setGridIsDrawn(bool draw=true)
Definition: qglviewer.h:130
octomath::Vector3::z
float & z()
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
qglviewer::Frame::orientation
Quaternion orientation() const
Definition: frame.cpp:546
QGLViewer::FRAME
@ FRAME
Definition: qglviewer.h:954
octomath::Vector3::x
float & x()
QGLViewer::gridIsDrawn
bool gridIsDrawn() const
Definition: qglviewer.h:101
octomap::ViewerWidget::postSelection
virtual void postSelection(const QPoint &)
Definition: ViewerWidget.cpp:390
octomath::Quaternion
octomap::ViewerWidget::jumpToCamFrame
void jumpToCamFrame(int id, int frame)
Definition: ViewerWidget.cpp:155
QGLViewer::camera
qglviewer::Camera * camera() const
Definition: qglviewer.h:250
qglviewer::KeyFrameInterpolator::stopInterpolation
void stopInterpolation()
Definition: keyFrameInterpolator.cpp:145
qglviewer::KeyFrameInterpolator
A keyFrame Catmull-Rom Frame interpolator.
Definition: keyFrameInterpolator.h:146
octomap::ViewerWidget::enableSelectionBox
void enableSelectionBox(bool enabled=true)
Definition: ViewerWidget.cpp:119
octomath::Pose6D::trans
Vector3 & trans()


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