main.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, 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/OdometryF2M.h>
00029 #include "rtabmap/core/Rtabmap.h"
00030 #include "rtabmap/core/RtabmapThread.h"
00031 #include "rtabmap/core/CameraRGBD.h"
00032 #include "rtabmap/core/CameraThread.h"
00033 #include "rtabmap/core/OdometryThread.h"
00034 #include "rtabmap/core/Graph.h"
00035 #include "rtabmap/utilite/UEventsManager.h"
00036 #include <QApplication>
00037 #include <stdio.h>
00038 #include <pcl/io/pcd_io.h>
00039 #include <pcl/io/ply_io.h>
00040 
00041 #include "MapBuilder.h"
00042 
00043 void showUsage()
00044 {
00045         printf("\nUsage:\n"
00046                         "rtabmap-rgbd_mapping driver\n"
00047                         "  driver       Driver number to use: 0=OpenNI-PCL, 1=OpenNI2, 2=Freenect, 3=OpenNI-CV, 4=OpenNI-CV-ASUS\n\n");
00048         exit(1);
00049 }
00050 
00051 using namespace rtabmap;
00052 int main(int argc, char * argv[])
00053 {
00054         ULogger::setType(ULogger::kTypeConsole);
00055         ULogger::setLevel(ULogger::kWarning);
00056 
00057         int driver = 0;
00058         if(argc < 2)
00059         {
00060                 showUsage();
00061         }
00062         else
00063         {
00064                 driver = atoi(argv[argc-1]);
00065                 if(driver < 0 || driver > 4)
00066                 {
00067                         UERROR("driver should be between 0 and 4.");
00068                         showUsage();
00069                 }
00070         }
00071 
00072         // Here is the pipeline that we will use:
00073         // CameraOpenni -> "CameraEvent" -> OdometryThread -> "OdometryEvent" -> RtabmapThread -> "RtabmapEvent"
00074 
00075         // Create the OpenNI camera, it will send a CameraEvent at the rate specified.
00076         // Set transform to camera so z is up, y is left and x going forward
00077         Camera * camera = 0;
00078         Transform opticalRotation(0,0,1,0, -1,0,0,0, 0,-1,0,0);
00079         if(driver == 1)
00080         {
00081                 if(!CameraOpenNI2::available())
00082                 {
00083                         UERROR("Not built with OpenNI2 support...");
00084                         exit(-1);
00085                 }
00086                 camera = new CameraOpenNI2("", 0, opticalRotation);
00087         }
00088         else if(driver == 2)
00089         {
00090                 if(!CameraFreenect::available())
00091                 {
00092                         UERROR("Not built with Freenect support...");
00093                         exit(-1);
00094                 }
00095                 camera = new CameraFreenect(0, 0, opticalRotation);
00096         }
00097         else if(driver == 3)
00098         {
00099                 if(!CameraOpenNICV::available())
00100                 {
00101                         UERROR("Not built with OpenNI from OpenCV support...");
00102                         exit(-1);
00103                 }
00104                 camera = new CameraOpenNICV(false, 0, opticalRotation);
00105         }
00106         else if(driver == 4)
00107         {
00108                 if(!CameraOpenNICV::available())
00109                 {
00110                         UERROR("Not built with OpenNI from OpenCV support...");
00111                         exit(-1);
00112                 }
00113                 camera = new CameraOpenNICV(true, 0, opticalRotation);
00114         }
00115         else
00116         {
00117                 camera = new rtabmap::CameraOpenni("", 0, opticalRotation);
00118         }
00119 
00120         if(!camera->init())
00121         {
00122                 UERROR("Camera init failed!");
00123         }
00124 
00125         CameraThread cameraThread(camera);
00126 
00127 
00128         // GUI stuff, there the handler will receive RtabmapEvent and construct the map
00129         // We give it the camera so the GUI can pause/resume the camera
00130         QApplication app(argc, argv);
00131         MapBuilder mapBuilder(&cameraThread);
00132 
00133         // Create an odometry thread to process camera events, it will send OdometryEvent.
00134         OdometryThread odomThread(new OdometryF2M());
00135 
00136 
00137         // Create RTAB-Map to process OdometryEvent
00138         Rtabmap * rtabmap = new Rtabmap();
00139         rtabmap->init();
00140         RtabmapThread rtabmapThread(rtabmap); // ownership is transfered
00141 
00142         // Setup handlers
00143         odomThread.registerToEventsManager();
00144         rtabmapThread.registerToEventsManager();
00145         mapBuilder.registerToEventsManager();
00146 
00147         // The RTAB-Map is subscribed by default to CameraEvent, but we want
00148         // RTAB-Map to process OdometryEvent instead, ignoring the CameraEvent.
00149         // We can do that by creating a "pipe" between the camera and odometry, then
00150         // only the odometry will receive CameraEvent from that camera. RTAB-Map is
00151         // also subscribed to OdometryEvent by default, so no need to create a pipe between
00152         // odometry and RTAB-Map.
00153         UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
00154 
00155         // Let's start the threads
00156         rtabmapThread.start();
00157         odomThread.start();
00158         cameraThread.start();
00159 
00160         mapBuilder.show();
00161         app.exec(); // main loop
00162 
00163         // remove handlers
00164         mapBuilder.unregisterFromEventsManager();
00165         rtabmapThread.unregisterFromEventsManager();
00166         odomThread.unregisterFromEventsManager();
00167 
00168         // Kill all threads
00169         cameraThread.kill();
00170         odomThread.join(true);
00171         rtabmapThread.join(true);
00172 
00173         // Save 3D map
00174         printf("Saving rtabmap_cloud.pcd...\n");
00175         std::map<int, Signature> nodes;
00176         std::map<int, Transform> optimizedPoses;
00177         std::multimap<int, Link> links;
00178         rtabmap->get3DMap(nodes, optimizedPoses, links, true, true);
00179         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00180         for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
00181         {
00182                 Signature node = nodes.find(iter->first)->second;
00183 
00184                 // uncompress data
00185                 node.sensorData().uncompressData();
00186 
00187                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp = util3d::cloudRGBFromSensorData(
00188                                 node.sensorData(),
00189                                 4,           // image decimation before creating the clouds
00190                                 4.0f,        // maximum depth of the cloud
00191                                 0.01f);  // Voxel grid filtering
00192                 *cloud += *util3d::transformPointCloud(tmp, iter->second); // transform the point cloud to its pose
00193         }
00194         if(cloud->size())
00195         {
00196                 printf("Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01f, (int)cloud->size());
00197                 cloud = util3d::voxelize(cloud, 0.01f);
00198 
00199                 printf("Saving rtabmap_cloud.pcd... done! (%d points)\n", (int)cloud->size());
00200                 pcl::io::savePCDFile("rtabmap_cloud.pcd", *cloud);
00201                 //pcl::io::savePLYFile("rtabmap_cloud.ply", *cloud); // to save in PLY format
00202         }
00203         else
00204         {
00205                 printf("Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
00206         }
00207 
00208         // Save trajectory
00209         printf("Saving rtabmap_trajectory.txt ...\n");
00210         if(optimizedPoses.size() && graph::exportPoses("rtabmap_trajectory.txt", 0, optimizedPoses, links))
00211         {
00212                 printf("Saving rtabmap_trajectory.txt... done!\n");
00213         }
00214         else
00215         {
00216                 printf("Saving rtabmap_trajectory.txt... failed!\n");
00217         }
00218 
00219         return 0;
00220 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:16