qtros.cpp
Go to the documentation of this file.
00001 /* This file is part of RGBDSLAM.
00002  * 
00003  * RGBDSLAM is free software: you can redistribute it and/or modify
00004  * it under the terms of the GNU General Public License as published by
00005  * the Free Software Foundation, either version 3 of the License, or
00006  * (at your option) any later version.
00007  * 
00008  * RGBDSLAM is distributed in the hope that it will be useful,
00009  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00010  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011  * GNU General Public License for more details.
00012  * 
00013  * You should have received a copy of the GNU General Public License
00014  * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
00015  */
00016 
00017 
00018 #include "qtros.h"
00019 
00020 QtROS::QtROS(int argc, char *argv[], const char* node_name) {
00021   std::cout << "Initializing Node...\n";
00022   ros::init(argc, argv, node_name);
00023   n = new ros::NodeHandle(node_name); //Use node name as Ros Namespace
00024   ROS_INFO("Connected to roscore");
00025   quitfromgui = false; 
00026 }
00027 
00028 void QtROS::quitNow(){ 
00029   quitfromgui = true; 
00030 }
00031 
00032 void QtROS::run(){ 
00033   ros::Rate r(30); // 30 hz. Kinect has 30hz and we are far from processing every frame anyhow.
00034   while(ros::ok() && !quitfromgui) {
00035     ros::spinOnce(); 
00036     r.sleep();}
00037   if (!quitfromgui) {
00038     Q_EMIT rosQuits();
00039     ROS_INFO("ROS-Node Terminated\n"); 
00040     ros::shutdown();//Not sure if necessary
00041   }
00042   ros::Duration d(0.5);
00043   d.sleep();
00044   exit(0);//Try Quick Exit
00045 }


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45