main.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 #include "openni_listener.h"
00018 #include "qtros.h"
00019 #include <QApplication>
00020 #include <QObject>
00021 #include "qt_gui.h"
00022 #include <Eigen/Core>
00023 #include "parameter_server.h"
00024 #include "ros_service_ui.h"
00025 
00026 //TODO:
00027 //better potential-edge-selection through flann
00028 //Better separation of function, communication, parameters and gui
00029 
00031 void ui_connections(QObject* ui, GraphManager* graph_mgr, OpenNIListener* listener)
00032 {
00033     QObject::connect(ui, SIGNAL(reset()), graph_mgr, SLOT(reset()));
00034     QObject::connect(ui, SIGNAL(optimizeGraph()), graph_mgr, SLOT(optimizeGraph()));
00035     QObject::connect(ui, SIGNAL(togglePause()), listener, SLOT(togglePause()));
00036     QObject::connect(ui, SIGNAL(toggleBagRecording()), listener, SLOT(toggleBagRecording()));
00037     QObject::connect(ui, SIGNAL(getOneFrame()), listener, SLOT(getOneFrame()));
00038     QObject::connect(ui, SIGNAL(deleteLastFrame()), graph_mgr, SLOT(deleteLastFrame()));
00039     QObject::connect(ui, SIGNAL(sendAllClouds()), graph_mgr, SLOT(sendAllClouds()));
00040     QObject::connect(ui, SIGNAL(saveAllClouds(QString)), graph_mgr, SLOT(saveAllClouds(QString)));
00041     QObject::connect(ui, SIGNAL(saveAllFeatures(QString)), graph_mgr, SLOT(saveAllFeatures(QString)));
00042     QObject::connect(ui, SIGNAL(saveIndividualClouds(QString)), graph_mgr, SLOT(saveIndividualClouds(QString)));
00043     QObject::connect(ui, SIGNAL(setMaxDepth(float)), graph_mgr, SLOT(setMaxDepth(float)));
00044     QObject::connect(ui, SIGNAL(saveTrajectory(QString)), graph_mgr, SLOT(saveTrajectory(QString)));
00045     QObject::connect(ui, SIGNAL(toggleMapping(bool)), graph_mgr, SLOT(toggleMapping(bool)));
00046 }
00047 
00049 void gui_connections(Graphical_UI* gui, GraphManager* graph_mgr, OpenNIListener* listener)
00050 {
00051     QObject::connect(listener,  SIGNAL(newVisualImage(QImage)), gui, SLOT(setVisualImage(QImage)));
00052     QObject::connect(listener,  SIGNAL(newFeatureFlowImage(QImage)), gui, SLOT(setFeatureFlowImage(QImage)));
00053     QObject::connect(listener,  SIGNAL(newDepthImage(QImage)), gui, SLOT(setDepthImage(QImage)));
00054     QObject::connect(graph_mgr, SIGNAL(sendFinished()), gui, SLOT(sendFinished()));
00055     QObject::connect(graph_mgr, SIGNAL(setGUIInfo(QString)), gui, SLOT(setInfo(QString)));
00056     QObject::connect(graph_mgr, SIGNAL(setGUIStatus(QString)), gui, SLOT(setStatus(QString)));
00057     QObject::connect(gui, SIGNAL(printEdgeErrors(QString)), graph_mgr, SLOT(printEdgeErrors(QString)));
00058     QObject::connect(gui, SIGNAL(pruneEdgesWithErrorAbove(float)), graph_mgr, SLOT(pruneEdgesWithErrorAbove(float)));
00059     if (ParameterServer::instance()->get<bool>("use_glwidget") && gui->getGLViewer() != NULL) {
00060       GLViewer* glv = gui->getGLViewer();
00061             QObject::connect(graph_mgr, SIGNAL(setPointCloud(pointcloud_type *, QMatrix4x4)), glv, SLOT(addPointCloud(pointcloud_type *, QMatrix4x4))); //, Qt::DirectConnection);
00062             QObject::connect(graph_mgr, SIGNAL(setGraphEdges(QList<QPair<int, int> >*)), glv, SLOT(setEdges(QList<QPair<int, int> >*)));
00063             QObject::connect(graph_mgr, SIGNAL(updateTransforms(QList<QMatrix4x4>*)), glv, SLOT(updateTransforms(QList<QMatrix4x4>*)));
00064       QObject::connect(graph_mgr, SIGNAL(deleteLastNode()), glv, SLOT(deleteLastNode()));
00065             QObject::connect(graph_mgr, SIGNAL(resetGLViewer()),  glv, SLOT(reset()));
00066       if(!ParameterServer::instance()->get<bool>("store_pointclouds")) {
00067           QObject::connect(glv, SIGNAL(cloudRendered(pointcloud_type const *)), graph_mgr, SLOT(cloudRendered(pointcloud_type const *))); // 
00068       }
00069     }
00070     QObject::connect(listener, SIGNAL(setGUIInfo(QString)), gui, SLOT(setInfo(QString)));
00071     QObject::connect(listener, SIGNAL(setGUIStatus(QString)), gui, SLOT(setStatus(QString)));
00072     QObject::connect(graph_mgr, SIGNAL(setGUIInfo2(QString)), gui, SLOT(setInfo2(QString)));
00073 }
00074 
00085 int main(int argc, char** argv)
00086 {
00087   setlocale(LC_NUMERIC,"C");//Avoid expecting german decimal separators in launch files
00088 
00089   //create thread object, to run the ros event processing loop in parallel to the qt loop
00090   QtROS qtRos(argc, argv, "rgbdslam"); //ros node name & namespace
00091 
00092   //Depending an use_gui on the Parameter Server, a gui- or a headless application is used
00093   QApplication app(argc, argv, ParameterServer::instance()->get<bool>("use_gui")); 
00094 
00095   GraphManager graph_mgr(qtRos.getNodeHandle());
00096 
00097   //Instantiate the kinect image listener
00098   OpenNIListener listener(qtRos.getNodeHandle(), &graph_mgr);
00099   QObject::connect(&listener, SIGNAL(bagFinished()), &qtRos, SLOT(quitNow()));
00100 
00101 
00102   Graphical_UI* gui = NULL;
00103         if (app.type() == QApplication::GuiClient){
00104       gui = new Graphical_UI();
00105       gui->show();
00106       gui_connections(gui, &graph_mgr, &listener);
00107       ui_connections(gui, &graph_mgr, &listener);//common connections for the user interfaces
00108   } else {
00109       ROS_WARN("Running without graphical user interface! See README for how to interact with RGBDSLAM.");
00110   }
00111   //Create Ros service interface with or without gui
00112   RosUi ui("rgbdslam"); //ui namespace for service calls
00113   ui_connections(&ui, &graph_mgr, &listener);//common connections for the user interfaces
00114 
00115   //If one thread receives a exit signal from the user, signal the other thread to quit too
00116   QObject::connect(&app, SIGNAL(aboutToQuit()), &qtRos, SLOT(quitNow()));
00117   QObject::connect(&qtRos, SIGNAL(rosQuits()), &app, SLOT(quit()));
00118   QObject::connect(&listener, SIGNAL(bagFinished()), &app, SLOT(quit()));
00119 
00120 
00121 
00122 #ifdef USE_ICP_BIN
00123   ROS_INFO_COND(ParameterServer::instance()->get<bool>("use_icp"), "ICP activated via external binary");
00124 #endif
00125 #ifdef USE_ICP_CODE
00126   ROS_INFO_COND(ParameterServer::instance()->get<bool>("use_icp"), "ICP activated via linked library");
00127 #endif
00128 
00129   qtRos.start();// Run main loop.
00130   app.exec();
00131   if(ros::ok()) ros::shutdown();//If not yet done through the qt connection
00132   ros::waitForShutdown(); //not sure if necessary. 
00133   //delete gui;
00134 }
00135 
00136 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


rgbdslam
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Wed Dec 26 2012 15:53:08