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 #include <octovis/CameraFollowMode.h>
00027 #include <iostream>
00028 
00029 #define CAMERA_PATH_ID 13
00030 #define ROBOT_TRAJECTORY_ID 14
00031 
00032 CameraFollowMode::CameraFollowMode(octomap::ScanGraph *graph)
00033 : QObject(), m_scan_graph(graph), m_current_scan(1), m_current_cam_frame(1), m_number_cam_frames(0),
00034   m_followRobotTrajectory(false) {
00035 }
00036 
00037 CameraFollowMode::~CameraFollowMode() {
00038 }
00039 
00040 
00041 void CameraFollowMode::jumpToFrame(unsigned int frame) {
00042   if(m_followRobotTrajectory) {
00043     if(frame <= m_scan_graph->size()) {
00044       m_current_scan = frame;
00045       octomath::Pose6D pose = m_scan_graph->getNodeByID(frame-1)->pose;
00046       emit changeCamPose(pose);
00047     }
00048   } else {
00049     m_current_cam_frame = frame;
00050     emit jumpToCamFrame(CAMERA_PATH_ID, m_current_cam_frame-1);
00051   }
00052 }
00053 
00054 void CameraFollowMode::play() {
00055   if(m_followRobotTrajectory) {
00056     emit deleteCameraPath(ROBOT_TRAJECTORY_ID);
00057     
00058     m_start_frame = m_current_scan;
00059     for(unsigned int i = m_start_frame; i <= m_scan_graph->size(); i++) {
00060       octomap::ScanNode* scanNode = m_scan_graph->getNodeByID(i-1);
00061       if (scanNode)
00062         emit appendToCameraPath(ROBOT_TRAJECTORY_ID, scanNode->pose);
00063       else{
00064         std::cerr << "Error in " << __FILE__ << ":" << __LINE__ <<" : invalid node ID "<< i-1 << std::endl;
00065       }
00066     }
00067     emit playCameraPath(ROBOT_TRAJECTORY_ID, 0);
00068   } else {
00069     m_start_frame = m_current_cam_frame;
00070     emit playCameraPath(CAMERA_PATH_ID, m_start_frame-1);
00071   }
00072 }
00073 
00074 void CameraFollowMode::pause() {
00075   emit stopCameraPath(CAMERA_PATH_ID);
00076   emit stopCameraPath(ROBOT_TRAJECTORY_ID);
00077 }
00078 
00079 
00080 void CameraFollowMode::setScanGraph(octomap::ScanGraph *graph) {
00081   m_scan_graph = graph;
00082   emit scanGraphAvailable(true);
00083 }
00084 
00085 void CameraFollowMode::cameraPathStopped(int id) {
00086   if(id == CAMERA_PATH_ID || id == ROBOT_TRAJECTORY_ID) {
00087     emit stopped();
00088   }
00089 }
00090 
00091 void CameraFollowMode::cameraPathFrameChanged(int id, int current_camera_frame) {
00092   if(m_followRobotTrajectory) {
00093     m_current_scan = m_start_frame + current_camera_frame;
00094     emit frameChanged(m_current_scan);
00095   } else {
00096     m_current_cam_frame = m_start_frame + current_camera_frame;
00097     emit frameChanged(m_current_cam_frame);
00098   }
00099 }
00100 
00101 void CameraFollowMode::clearCameraPath() {
00102   emit deleteCameraPath(CAMERA_PATH_ID);
00103   m_current_cam_frame = 1;
00104   m_number_cam_frames = 0;
00105   emit frameChanged(m_current_cam_frame);
00106   emit changeNumberOfFrames(m_number_cam_frames);
00107 }
00108 
00109 void CameraFollowMode::saveToCameraPath() {
00110   emit updateCameraPath(CAMERA_PATH_ID, m_current_cam_frame-1);
00111 }
00112 
00113 void CameraFollowMode::addToCameraPath() {
00114   emit addCurrentToCameraPath(CAMERA_PATH_ID, m_current_cam_frame-1);
00115   m_number_cam_frames++;
00116   if(m_number_cam_frames == 1) m_current_cam_frame = 1;
00117   else m_current_cam_frame++;
00118   emit frameChanged(m_current_cam_frame);
00119   emit changeNumberOfFrames(m_number_cam_frames);
00120 }
00121 
00122 void CameraFollowMode::removeFromCameraPath() {
00123   if(m_number_cam_frames>0) {
00124     emit removeFromCameraPath(CAMERA_PATH_ID, m_current_cam_frame-1);
00125     m_number_cam_frames--;
00126     emit changeNumberOfFrames(m_number_cam_frames);
00127   }
00128 }
00129 
00130 void CameraFollowMode::followCameraPath() {
00131   m_followRobotTrajectory = false;
00132   emit frameChanged(m_current_cam_frame);
00133   emit changeNumberOfFrames(m_number_cam_frames);
00134 }
00135 
00136 void CameraFollowMode::followRobotPath() {
00137   if(m_scan_graph) {
00138     m_followRobotTrajectory = true;
00139     emit frameChanged(m_current_scan);
00140     emit changeNumberOfFrames(m_scan_graph->size());
00141   }
00142 }