main.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/core/Rtabmap.h"
00029 #include "rtabmap/core/RtabmapThread.h"
00030 #include "rtabmap/core/CameraRGBD.h"
00031 #include "rtabmap/core/CameraThread.h"
00032 #include "rtabmap/core/Odometry.h"
00033 #include "rtabmap/core/OdometryThread.h"
00034 #include "rtabmap/utilite/UEventsManager.h"
00035 #include <QApplication>
00036 #include <stdio.h>
00037 
00038 #include "MapBuilder.h"
00039 
00040 void showUsage()
00041 {
00042         printf("\nUsage:\n"
00043                         "rtabmap-rgbd_mapping driver\n"
00044                         "  driver       Driver number to use: 0=OpenNI-PCL, 1=OpenNI2, 2=Freenect, 3=OpenNI-CV, 4=OpenNI-CV-ASUS\n\n");
00045         exit(1);
00046 }
00047 
00048 using namespace rtabmap;
00049 int main(int argc, char * argv[])
00050 {
00051         ULogger::setType(ULogger::kTypeConsole);
00052         ULogger::setLevel(ULogger::kWarning);
00053 
00054         int driver = 0;
00055         if(argc < 2)
00056         {
00057                 showUsage();
00058         }
00059         else
00060         {
00061                 driver = atoi(argv[argc-1]);
00062                 if(driver < 0 || driver > 4)
00063                 {
00064                         UERROR("driver should be between 0 and 4.");
00065                         showUsage();
00066                 }
00067         }
00068 
00069         // Here is the pipeline that we will use:
00070         // CameraOpenni -> "CameraEvent" -> OdometryThread -> "OdometryEvent" -> RtabmapThread -> "RtabmapEvent"
00071 
00072         // Create the OpenNI camera, it will send a CameraEvent at the rate specified.
00073         // Set transform to camera so z is up, y is left and x going forward
00074         CameraRGBD * camera = 0;
00075         Transform opticalRotation(0,0,1,0, -1,0,0,0, 0,-1,0,0);
00076         if(driver == 1)
00077         {
00078                 if(!CameraOpenNI2::available())
00079                 {
00080                         UERROR("Not built with OpenNI2 support...");
00081                         exit(-1);
00082                 }
00083                 camera = new CameraOpenNI2("", 0, opticalRotation);
00084         }
00085         else if(driver == 2)
00086         {
00087                 if(!CameraFreenect::available())
00088                 {
00089                         UERROR("Not built with Freenect support...");
00090                         exit(-1);
00091                 }
00092                 camera = new CameraFreenect(0, 0, opticalRotation);
00093         }
00094         else if(driver == 3)
00095         {
00096                 if(!CameraOpenNICV::available())
00097                 {
00098                         UERROR("Not built with OpenNI from OpenCV support...");
00099                         exit(-1);
00100                 }
00101                 camera = new CameraOpenNICV(false, 0, opticalRotation);
00102         }
00103         else if(driver == 4)
00104         {
00105                 if(!CameraOpenNICV::available())
00106                 {
00107                         UERROR("Not built with OpenNI from OpenCV support...");
00108                         exit(-1);
00109                 }
00110                 camera = new CameraOpenNICV(true, 0, opticalRotation);
00111         }
00112         else
00113         {
00114                 camera = new rtabmap::CameraOpenni("", 0, opticalRotation);
00115         }
00116 
00117         CameraThread cameraThread(camera);
00118         if(!cameraThread.init())
00119         {
00120                 UERROR("Camera init failed!");
00121                 exit(1);
00122         }
00123 
00124         // GUI stuff, there the handler will receive RtabmapEvent and construct the map
00125         // We give it the camera so the GUI can pause/resume the camera
00126         QApplication app(argc, argv);
00127         MapBuilder mapBuilder(&cameraThread);
00128 
00129         // Create an odometry thread to process camera events, it will send OdometryEvent.
00130         OdometryThread odomThread(new OdometryBOW());
00131 
00132 
00133         // Create RTAB-Map to process OdometryEvent
00134         Rtabmap * rtabmap = new Rtabmap();
00135         rtabmap->init();
00136         RtabmapThread rtabmapThread(rtabmap); // ownership is transfered
00137 
00138         // Setup handlers
00139         odomThread.registerToEventsManager();
00140         rtabmapThread.registerToEventsManager();
00141         mapBuilder.registerToEventsManager();
00142 
00143         // The RTAB-Map is subscribed by default to CameraEvent, but we want
00144         // RTAB-Map to process OdometryEvent instead, ignoring the CameraEvent.
00145         // We can do that by creating a "pipe" between the camera and odometry, then
00146         // only the odometry will receive CameraEvent from that camera. RTAB-Map is
00147         // also subscribed to OdometryEvent by default, so no need to create a pipe between
00148         // odometry and RTAB-Map.
00149         UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
00150 
00151         // Let's start the threads
00152         rtabmapThread.start();
00153         odomThread.start();
00154         cameraThread.start();
00155 
00156         mapBuilder.show();
00157         app.exec(); // main loop
00158 
00159         // remove handlers
00160         mapBuilder.unregisterFromEventsManager();
00161         rtabmapThread.unregisterFromEventsManager();
00162         odomThread.unregisterFromEventsManager();
00163 
00164         // Kill all threads
00165         cameraThread.kill();
00166         odomThread.join(true);
00167         rtabmapThread.join(true);
00168 
00169         return 0;
00170 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:31