CameraFollowMode.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 
26 #include <iostream>
27 
28 #define CAMERA_PATH_ID 13
29 #define ROBOT_TRAJECTORY_ID 14
30 
32 : QObject(), m_scan_graph(graph), m_current_scan(1), m_current_cam_frame(1), m_number_cam_frames(0),
33  m_followRobotTrajectory(false) {
34 }
35 
37 }
38 
39 
40 void CameraFollowMode::jumpToFrame(unsigned int frame) {
42  if(frame <= m_scan_graph->size()) {
43  m_current_scan = frame;
45  emit changeCamPose(pose);
46  }
47  } else {
48  m_current_cam_frame = frame;
50  }
51 }
52 
56  //emit appendCurrentToCameraPath(ROBOT_TRAJECTORY_ID);
58  for(unsigned int i = m_start_frame; i <= m_scan_graph->size(); i++) {
59  octomap::ScanNode* scanNode = m_scan_graph->getNodeByID(i-1);
60  if (scanNode)
62  else{
63  std::cerr << "Error in " << __FILE__ << ":" << __LINE__ <<" : invalid node ID "<< i-1 << std::endl;
64  }
65  }
67  } else {
70  }
71 }
72 
76 }
77 
78 
80  m_scan_graph = graph;
81  emit scanGraphAvailable(true);
82 }
83 
85  if(id == CAMERA_PATH_ID || id == ROBOT_TRAJECTORY_ID) {
86  emit stopped();
87  }
88 }
89 
90 void CameraFollowMode::cameraPathFrameChanged(int id, int current_camera_frame) {
92  m_current_scan = m_start_frame + current_camera_frame;
94  } else {
95  m_current_cam_frame = m_start_frame + current_camera_frame;
97  }
98 }
99 
106 }
107 
110 }
111 
116  else m_current_cam_frame++;
119 }
120 
122  if(m_number_cam_frames>0) {
126  }
127 }
128 
130  m_followRobotTrajectory = false;
133 }
134 
136  if(m_scan_graph) {
140  }
141 }
CameraFollowMode::cameraPathStopped
void cameraPathStopped(int id)
Definition: CameraFollowMode.cpp:84
CameraFollowMode::removeFromCameraPath
void removeFromCameraPath()
Definition: CameraFollowMode.cpp:121
CameraFollowMode::playCameraPath
void playCameraPath(int id, int start_frame)
CameraFollowMode::followRobotPath
void followRobotPath()
Definition: CameraFollowMode.cpp:135
CameraFollowMode::changeCamPose
void changeCamPose(const octomath::Pose6D &pose)
CameraFollowMode::addCurrentToCameraPath
void addCurrentToCameraPath(int id, int frame)
octomap::ScanNode::pose
pose6d pose
CameraFollowMode::stopCameraPath
void stopCameraPath(int id)
ROBOT_TRAJECTORY_ID
#define ROBOT_TRAJECTORY_ID
Definition: CameraFollowMode.cpp:29
CameraFollowMode::m_scan_graph
octomap::ScanGraph * m_scan_graph
Definition: CameraFollowMode.h:71
CameraFollowMode::updateCameraPath
void updateCameraPath(int id, int frame)
CameraFollowMode::m_current_cam_frame
unsigned int m_current_cam_frame
Definition: CameraFollowMode.h:73
CameraFollowMode::jumpToCamFrame
void jumpToCamFrame(int id, int frame)
CameraFollowMode::cameraPathFrameChanged
void cameraPathFrameChanged(int id, int current_camera_frame)
Definition: CameraFollowMode.cpp:90
CameraFollowMode::setScanGraph
void setScanGraph(octomap::ScanGraph *graph)
Definition: CameraFollowMode.cpp:79
CameraFollowMode::m_current_scan
unsigned int m_current_scan
Definition: CameraFollowMode.h:72
CameraFollowMode::stopped
void stopped()
CameraFollowMode.h
octomap::ScanGraph
CameraFollowMode::pause
void pause()
Definition: CameraFollowMode.cpp:73
CameraFollowMode::m_start_frame
unsigned int m_start_frame
Definition: CameraFollowMode.h:75
octomap::ScanNode
CameraFollowMode::play
void play()
Definition: CameraFollowMode.cpp:53
octomap::ScanGraph::size
size_t size() const
octomap::ScanGraph::getNodeByID
ScanNode * getNodeByID(unsigned int id)
CameraFollowMode::addToCameraPath
void addToCameraPath()
Definition: CameraFollowMode.cpp:112
CameraFollowMode::frameChanged
void frameChanged(unsigned int frame)
CameraFollowMode::changeNumberOfFrames
void changeNumberOfFrames(unsigned count)
CameraFollowMode::scanGraphAvailable
void scanGraphAvailable(bool available)
CameraFollowMode::clearCameraPath
void clearCameraPath()
Definition: CameraFollowMode.cpp:100
CameraFollowMode::jumpToFrame
void jumpToFrame(unsigned int frame)
Definition: CameraFollowMode.cpp:40
CAMERA_PATH_ID
#define CAMERA_PATH_ID
Definition: CameraFollowMode.cpp:28
CameraFollowMode::~CameraFollowMode
virtual ~CameraFollowMode()
Definition: CameraFollowMode.cpp:36
CameraFollowMode::saveToCameraPath
void saveToCameraPath()
Definition: CameraFollowMode.cpp:108
octomath::Pose6D
CameraFollowMode::appendToCameraPath
void appendToCameraPath(int id, const octomath::Pose6D &pose)
CameraFollowMode::deleteCameraPath
void deleteCameraPath(int id)
CameraFollowMode::m_followRobotTrajectory
bool m_followRobotTrajectory
Definition: CameraFollowMode.h:76
CameraFollowMode::CameraFollowMode
CameraFollowMode(octomap::ScanGraph *graph=NULL)
Definition: CameraFollowMode.cpp:31
CameraFollowMode::m_number_cam_frames
unsigned int m_number_cam_frames
Definition: CameraFollowMode.h:74
CameraFollowMode::followCameraPath
void followCameraPath()
Definition: CameraFollowMode.cpp:129


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