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 "glviewer.h"
00023 #include <Eigen/Core>
00024 #include "parameter_server.h"
00025 #include "ros_service_ui.h"
00026 
00027 //TODO:
00028 //better potential-edge-selection through flann or place recognition
00029 //Better separation of function, communication, parameters and gui
00030 //Better integration of the calibration data
00031 //Correct implementation of odometry
00032 //Multi-Camera-fusion
00033 
00034 class Renderable; //Fwd decl for signal renderableOctomap
00036 void ui_connections(QObject* ui, GraphManager* graph_mgr, OpenNIListener* listener)
00037 {
00038   Qt::ConnectionType ctype = Qt::AutoConnection;
00039   if (ParameterServer::instance()->get<bool>("concurrent_io")) 
00040     ctype = Qt::DirectConnection;
00041   QObject::connect(ui, SIGNAL(reset()), graph_mgr, SLOT(reset()), ctype);
00042   QObject::connect(ui, SIGNAL(optimizeGraph()), graph_mgr, SLOT(optimizeGraph()), ctype);
00043   QObject::connect(ui, SIGNAL(togglePause()), listener, SLOT(togglePause()), ctype);
00044   QObject::connect(ui, SIGNAL(getOneFrame()), listener, SLOT(getOneFrame()), ctype);
00045   QObject::connect(ui, SIGNAL(deleteLastFrame()), graph_mgr, SLOT(deleteLastFrame()), ctype);
00046   QObject::connect(ui, SIGNAL(sendAllClouds()), graph_mgr, SLOT(sendAllClouds()), ctype);
00047   QObject::connect(ui, SIGNAL(saveAllClouds(QString)), graph_mgr, SLOT(saveAllClouds(QString)), ctype);
00048   QObject::connect(ui, SIGNAL(saveOctomapSig(QString)), graph_mgr, SLOT(saveOctomap(QString)), ctype);
00049   QObject::connect(ui, SIGNAL(saveAllFeatures(QString)), graph_mgr, SLOT(saveAllFeatures(QString)), ctype);
00050   QObject::connect(ui, SIGNAL(saveIndividualClouds(QString)), graph_mgr, SLOT(saveIndividualClouds(QString)), ctype);
00051   QObject::connect(ui, SIGNAL(saveTrajectory(QString)), graph_mgr, SLOT(saveTrajectory(QString)), ctype);
00052   QObject::connect(ui, SIGNAL(toggleMapping(bool)), graph_mgr, SLOT(toggleMapping(bool)), ctype);
00053   QObject::connect(ui, SIGNAL(saveG2OGraph(QString)), graph_mgr, SLOT(saveG2OGraph(QString)), ctype);
00054 }
00055 
00057 void gui_connections(Graphical_UI* gui, GraphManager* graph_mgr, OpenNIListener* listener)
00058 {
00059     QObject::connect(listener,  SIGNAL(newVisualImage(QImage)), gui, SLOT(setVisualImage(QImage)));
00060     QObject::connect(listener,  SIGNAL(newFeatureFlowImage(QImage)), gui, SLOT(setFeatureFlowImage(QImage)));
00061     QObject::connect(listener,  SIGNAL(newFeatureImage(QImage)), gui, SLOT(setFeatureImage(QImage)));
00062     QObject::connect(listener,  SIGNAL(newDepthImage(QImage)), gui, SLOT(setDepthImage(QImage)));
00063     QObject::connect(graph_mgr, SIGNAL(sendFinished()), gui, SLOT(sendFinished()));
00064     QObject::connect(graph_mgr, SIGNAL(iamBusy(int, const char*, int)), gui, SLOT(showBusy(int, const char*, int)));
00065     QObject::connect(graph_mgr, SIGNAL(progress(int, const char*, int)), gui, SLOT(setBusy(int, const char*, int)));
00066     QObject::connect(listener, SIGNAL(iamBusy(int, const char*, int)), gui, SLOT(showBusy(int, const char*, int)));
00067     QObject::connect(listener, SIGNAL(progress(int, const char*, int)), gui, SLOT(setBusy(int, const char*, int)));
00068     QObject::connect(graph_mgr, SIGNAL(setGUIInfo(QString)), gui, SLOT(setInfo(QString)));
00069     QObject::connect(graph_mgr, SIGNAL(setGUIStatus(QString)), gui, SLOT(setStatus(QString)));
00070     QObject::connect(gui, SIGNAL(printEdgeErrors(QString)), graph_mgr, SLOT(printEdgeErrors(QString)));
00071     QObject::connect(gui, SIGNAL(pruneEdgesWithErrorAbove(float)), graph_mgr, SLOT(pruneEdgesWithErrorAbove(float)));
00072     QObject::connect(gui, SIGNAL(clearClouds()), graph_mgr, SLOT(clearPointClouds()));
00073     QObject::connect(gui, SIGNAL(occupancyFilterClouds()), graph_mgr, SLOT(occupancyFilterClouds()));
00074     QObject::connect(gui, SIGNAL(saveBagfile(QString)), graph_mgr, SLOT(saveBagfileAsync(QString)));
00075     QObject::connect(gui, SIGNAL(openPCDFiles(QStringList)), listener, SLOT(loadPCDFiles(QStringList)));
00076     QObject::connect(gui, SIGNAL(openBagFile(QString)), listener, SLOT(loadBagFileFromGUI(QString)));
00077     if (ParameterServer::instance()->get<bool>("use_glwidget") && gui->getGLViewer() != NULL) {
00078       GLViewer* glv = gui->getGLViewer();
00079             QObject::connect(graph_mgr, SIGNAL(setPointCloud(pointcloud_type *, QMatrix4x4)), glv, SLOT(addPointCloud(pointcloud_type *, QMatrix4x4)), Qt::BlockingQueuedConnection ); //Needs to block, otherwise the opengl list compilation makes the app unresponsive. This effectively throttles the processing rate though
00080       typedef const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >* cnst_ft_vectors;
00081             QObject::connect(graph_mgr, SIGNAL(setFeatures(const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >*)), glv, SLOT(addFeatures(const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >*))); //, Qt::DirectConnection);
00082             QObject::connect(graph_mgr, SIGNAL(setGraphEdges(const QList<QPair<int, int> >*)), glv, SLOT(setEdges(const QList<QPair<int, int> >*)));
00083             QObject::connect(graph_mgr, SIGNAL(updateTransforms(QList<QMatrix4x4>*)), glv, SLOT(updateTransforms(QList<QMatrix4x4>*)));
00084       QObject::connect(graph_mgr, SIGNAL(deleteLastNode()), glv, SLOT(deleteLastNode()));
00085             QObject::connect(graph_mgr, SIGNAL(resetGLViewer()),  glv, SLOT(reset()));
00086             QObject::connect(graph_mgr, SIGNAL(renderableOctomap(Renderable*)),  glv, SLOT(setRenderable(Renderable*)));
00087       //QObject::connect(glv, SIGNAL(clickedPosition(float,float,float)), graph_mgr, SLOT(filterNodesByPosition(float,float,float)));
00088       if(!ParameterServer::instance()->get<bool>("store_pointclouds")) {
00089           QObject::connect(glv, SIGNAL(cloudRendered(pointcloud_type *)), graph_mgr, SLOT(clearPointCloud(pointcloud_type const *))); // 
00090       } else if(ParameterServer::instance()->get<double>("voxelfilter_size") > 0.0) {
00091           QObject::connect(glv, SIGNAL(cloudRendered(pointcloud_type *)), graph_mgr, SLOT(reducePointCloud(pointcloud_type const *))); // 
00092       }
00093     }
00094     QObject::connect(listener, SIGNAL(setGUIInfo(QString)), gui, SLOT(setInfo(QString)));
00095     QObject::connect(listener, SIGNAL(setGUIStatus(QString)), gui, SLOT(setStatus(QString)));
00096     QObject::connect(listener, SIGNAL(setGUIInfo2(QString)), gui, SLOT(setInfo2(QString)));
00097     QObject::connect(graph_mgr, SIGNAL(setGUIInfo2(QString)), gui, SLOT(setInfo2(QString)));
00098 }
00099 
00110 int main(int argc, char** argv)
00111 {
00112   setlocale(LC_NUMERIC,"C");//Avoid expecting german decimal separators in launch files
00113 
00114   //create thread object, to run the ros event processing loop in parallel to the qt loop
00115   QtROS qtRos(argc, argv, "rgbdslam"); //ros node name & namespace
00116 
00117   //Depending an use_gui on the Parameter Server, a gui- or a headless application is used
00118   QApplication app(argc, argv, ParameterServer::instance()->get<bool>("use_gui")); 
00119 
00120   GraphManager graph_mgr;
00121   //Instantiate the kinect image listener
00122   OpenNIListener listener(&graph_mgr);
00123   std::string bagfile_name = ParameterServer::instance()->get<std::string>("bagfile_name");
00124   if(!bagfile_name.empty()) 
00125   {
00126     QObject::connect(&listener, SIGNAL(bagFinished()), &app, SLOT(quit()));
00127     QObject::connect(&listener, SIGNAL(bagFinished()), &qtRos, SLOT(quitNow()));
00128     listener.loadBagFileFromGUI(bagfile_name.c_str());
00129     //QtConcurrent::run(&listener, &OpenNIListener::loadBag, bagfile_name);
00130   }
00131 
00132   Graphical_UI* gui = NULL;
00133         if (app.type() == QApplication::GuiClient){
00134       gui = new Graphical_UI();
00135       gui->show();
00136       gui_connections(gui, &graph_mgr, &listener);
00137       ui_connections(gui, &graph_mgr, &listener);//common connections for the user interfaces
00138   } else {
00139       ROS_WARN("Running without graphical user interface! See README or wiki page for how to interact with RGBDSLAM.");
00140   }
00141   //Create Ros service interface with or without gui
00142   RosUi ui("rgbdslam"); //ui namespace for service calls
00143   ui_connections(&ui, &graph_mgr, &listener);//common connections for the user interfaces
00144 
00145   //If one thread receives a exit signal from the user, signal the other thread to quit too
00146   QObject::connect(&app, SIGNAL(aboutToQuit()), &qtRos, SLOT(quitNow()));
00147   QObject::connect(&qtRos, SIGNAL(rosQuits()), &app, SLOT(quit()));
00148 
00149   qtRos.start();// Run main loop.
00150   app.exec();
00151   //if(ros::ok()) ros::shutdown();//If not yet done through the qt connection
00152   //ros::waitForShutdown(); //not sure if necessary. 
00153 }
00154 
00155 


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