CameraFollowMode.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 CAMERAFOLLOWMODE_H_
26 #define CAMERAFOLLOWMODE_H_
27 
28 #include "SceneObject.h"
29 
30 class CameraFollowMode : public QObject {
31  Q_OBJECT
32 
33 public:
34  CameraFollowMode(octomap::ScanGraph *graph = NULL);
35  virtual ~CameraFollowMode();
36  void setScanGraph(octomap::ScanGraph *graph);
37 
38 public slots:
39  void jumpToFrame(unsigned int frame);
40  void cameraPathStopped(int id);
41  void cameraPathFrameChanged(int id, int current_camera_frame);
42  void play();
43  void pause();
44  void clearCameraPath();
45  void saveToCameraPath();
46  void addToCameraPath();
47  void removeFromCameraPath();
48  void followCameraPath();
49  void followRobotPath();
50 
51 signals:
52  void changeCamPose(const octomath::Pose6D& pose);
53  void interpolateCamPose(const octomath::Pose6D& old_pose, const octomath::Pose6D& new_pose, double u);
54  void stopped();
55  void frameChanged(unsigned int frame);
56  void deleteCameraPath(int id);
57  void removeFromCameraPath(int id, int frame);
58  void updateCameraPath(int id, int frame);
59  void appendToCameraPath(int id, const octomath::Pose6D& pose);
60  void appendCurrentToCameraPath(int id);
61  void addCurrentToCameraPath(int id, int frame);
62  void playCameraPath(int id, int start_frame);
63  void stopCameraPath(int id);
64  void jumpToCamFrame(int id, int frame);
65  void changeNumberOfFrames(unsigned count);
66  void scanGraphAvailable(bool available);
67 
68 
69 protected:
71  unsigned int m_current_scan;
72  unsigned int m_current_cam_frame;
73  unsigned int m_number_cam_frames;
74  unsigned int m_start_frame;
76 };
77 
78 #endif /* CAMERAFOLLOWMODE_H_ */
CameraFollowMode(octomap::ScanGraph *graph=NULL)
void deleteCameraPath(int id)
unsigned int m_number_cam_frames
void cameraPathStopped(int id)
void playCameraPath(int id, int start_frame)
void frameChanged(unsigned int frame)
void appendToCameraPath(int id, const octomath::Pose6D &pose)
octomap::ScanGraph * m_scan_graph
void updateCameraPath(int id, int frame)
void setScanGraph(octomap::ScanGraph *graph)
unsigned int m_start_frame
void jumpToCamFrame(int id, int frame)
void stopCameraPath(int id)
void interpolateCamPose(const octomath::Pose6D &old_pose, const octomath::Pose6D &new_pose, double u)
void changeNumberOfFrames(unsigned count)
void addCurrentToCameraPath(int id, int frame)
unsigned int m_current_scan
void changeCamPose(const octomath::Pose6D &pose)
unsigned int m_current_cam_frame
void appendCurrentToCameraPath(int id)
void jumpToFrame(unsigned int frame)
void cameraPathFrameChanged(int id, int current_camera_frame)
virtual ~CameraFollowMode()
void scanGraphAvailable(bool available)


octovis
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Mon Jun 10 2019 14:00:24