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/utilite/ULogger.h>
00029 #include <rtabmap/utilite/UEventsManager.h>
00030 #include <rtabmap/utilite/UFile.h>
00031 #include <rtabmap/utilite/UConversion.h>
00032 #include <rtabmap/utilite/UStl.h>
00033 #include <rtabmap/core/OdometryF2F.h>
00034 #include <rtabmap/core/OdometryMono.h>
00035 #include <rtabmap/core/OdometryThread.h>
00036 #include <rtabmap/gui/OdometryViewer.h>
00037 #include <rtabmap/core/CameraThread.h>
00038 #include <rtabmap/core/CameraRGBD.h>
00039 #include <rtabmap/core/CameraStereo.h>
00040 #include <rtabmap/core/DBReader.h>
00041 #include <rtabmap/core/VWDictionary.h>
00042 #include <QApplication>
00043 #include <QPushButton>
00044 #include <pcl/console/print.h>
00045 #include <rtabmap/core/OdometryF2M.h>
00046 
00047 void showUsage()
00048 {
00049         printf("\nUsage:\n"
00050                         "odometryViewer [options]\n"
00051                         "Options:\n"
00052                         "  -driver #                 Driver number to use: 0=OpenNI-PCL, 1=OpenNI2, 2=Freenect, 3=OpenNI-CV, 4=OpenNI-CV-ASUS, 5=Freenect2, 6=dc1394, 7=FlyCapture2\n"
00053                         "  -hz #.#                   Camera rate (default 0, 0 means as fast as the camera can)\n"
00054                         "  -db \"input.db\"          Use database instead of camera (recorded with rtabmap-dataRecorder)\n"
00055                         "  -clouds #                 Maximum clouds shown (default 10, zero means inf)\n"
00056                         "  -sec #.#                  Delay (seconds) before reading the database (if set)\n"
00057                         "%s\n",
00058                         rtabmap::Parameters::showUsage());
00059         exit(1);
00060 }
00061 
00062 int main (int argc, char * argv[])
00063 {
00064         ULogger::setType(ULogger::kTypeConsole);
00065         ULogger::setLevel(ULogger::kInfo);
00066 
00067         // parse arguments
00068         float rate = 0.0;
00069         std::string inputDatabase;
00070         int driver = 0;
00071         int maxClouds = 10;
00072         float sec = 0.0f;
00073 
00074         for(int i=1; i<argc; ++i)
00075         {
00076                 if(strcmp(argv[i], "-driver") == 0)
00077                 {
00078                         ++i;
00079                         if(i < argc)
00080                         {
00081                                 driver = std::atoi(argv[i]);
00082                                 if(driver < 0 || driver > 7)
00083                                 {
00084                                         showUsage();
00085                                 }
00086                         }
00087                         else
00088                         {
00089                                 showUsage();
00090                         }
00091                         continue;
00092                 }
00093                 if(strcmp(argv[i], "-hz") == 0)
00094                 {
00095                         ++i;
00096                         if(i < argc)
00097                         {
00098                                 rate = uStr2Float(argv[i]);
00099                                 if(rate < 0)
00100                                 {
00101                                         showUsage();
00102                                 }
00103                         }
00104                         else
00105                         {
00106                                 showUsage();
00107                         }
00108                         continue;
00109                 }
00110                 if(strcmp(argv[i], "-db") == 0)
00111                 {
00112                         ++i;
00113                         if(i < argc)
00114                         {
00115                                 inputDatabase = argv[i];
00116                                 if(UFile::getExtension(inputDatabase).compare("db") != 0)
00117                                 {
00118                                         printf("Database path (%s) should end with \"db\" \n", inputDatabase.c_str());
00119                                         showUsage();
00120                                 }
00121                         }
00122                         else
00123                         {
00124                                 showUsage();
00125                         }
00126                         continue;
00127                 }
00128                 if(strcmp(argv[i], "-clouds") == 0)
00129                 {
00130                         ++i;
00131                         if(i < argc)
00132                         {
00133                                 maxClouds = std::atoi(argv[i]);
00134                                 if(maxClouds < 0)
00135                                 {
00136                                         showUsage();
00137                                 }
00138                         }
00139                         else
00140                         {
00141                                 showUsage();
00142                         }
00143                         continue;
00144                 }
00145                 if(strcmp(argv[i], "-sec") == 0)
00146                 {
00147                         ++i;
00148                         if(i < argc)
00149                         {
00150                                 sec = uStr2Float(argv[i]);
00151                                 if(sec < 0.0f)
00152                                 {
00153                                         showUsage();
00154                                 }
00155                         }
00156                         else
00157                         {
00158                                 showUsage();
00159                         }
00160                         continue;
00161                 }
00162                 if(strcmp(argv[i], "-help") == 0 || strcmp(argv[i], "--help") == 0)
00163                 {
00164                         showUsage();
00165                 }
00166         }
00167 
00168         if(inputDatabase.size())
00169         {
00170                 UINFO("Using database input \"%s\"", inputDatabase.c_str());
00171         }
00172         else
00173         {
00174                 UINFO("Using OpenNI camera");
00175         }
00176 
00177         UINFO("Camera rate =             %f Hz", rate);
00178         UINFO("Maximum clouds shown =    %d", maxClouds);
00179         UINFO("Delay =                   %f s", sec);
00180 
00181         rtabmap::ParametersMap parameters = rtabmap::Parameters::parseArguments(argc, argv);
00182         for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00183         {
00184                 UINFO(" Param \"%s\"=\"%s\"", iter->first.c_str(), iter->second.c_str());
00185         }
00186 
00187         bool icp = false;
00188         int regStrategy = rtabmap::Parameters::defaultRegStrategy();
00189         rtabmap::Parameters::parse(parameters, rtabmap::Parameters::kRegStrategy(), regStrategy);
00190         int decimation = 8;
00191         float maxDepth = 4.0f;
00192         float voxelSize = rtabmap::Parameters::defaultIcpVoxelSize();
00193         int normalsK = 0;
00194         if(regStrategy == 1 || regStrategy == 2)
00195         {
00196                 // icp requires scans
00197                 icp = true;
00198 
00199                 rtabmap::Parameters::parse(parameters, rtabmap::Parameters::kIcpDownsamplingStep(), decimation);
00200                 rtabmap::Parameters::parse(parameters, rtabmap::Parameters::kIcpVoxelSize(), voxelSize);
00201 
00202                 bool pointToPlane = rtabmap::Parameters::defaultIcpPointToPlane();
00203                 rtabmap::Parameters::parse(parameters, rtabmap::Parameters::kIcpPointToPlane(), pointToPlane);
00204                 if(pointToPlane)
00205                 {
00206                         normalsK = rtabmap::Parameters::defaultIcpPointToPlaneNormalNeighbors();
00207                         rtabmap::Parameters::parse(parameters, rtabmap::Parameters::kIcpPointToPlaneNormalNeighbors(), normalsK);
00208                 }
00209 
00210                 uInsert(parameters, rtabmap::ParametersPair(rtabmap::Parameters::kIcpDownsamplingStep(), "1"));
00211                 uInsert(parameters, rtabmap::ParametersPair(rtabmap::Parameters::kIcpVoxelSize(), "0"));
00212         }
00213 
00214         QApplication app(argc, argv);
00215 
00216         rtabmap::Odometry * odom = rtabmap::Odometry::create(parameters);
00217 
00218         rtabmap::OdometryThread odomThread(odom);
00219         rtabmap::OdometryViewer odomViewer(maxClouds, 2, 0.0, 50);
00220         UEventsManager::addHandler(&odomThread);
00221         UEventsManager::addHandler(&odomViewer);
00222 
00223         odomViewer.setWindowTitle("Odometry view");
00224         odomViewer.resize(1280, 480+QPushButton().minimumHeight());
00225 
00226         rtabmap::Camera * camera = 0;
00227         rtabmap::Transform t=rtabmap::Transform(0,0,1,0, -1,0,0,0, 0,-1,0,0);
00228 
00229         if(inputDatabase.size())
00230         {
00231                 camera =  new rtabmap::DBReader(inputDatabase, rate, true);
00232         }
00233         else if(driver == 0)
00234         {
00235                 camera = new rtabmap::CameraOpenni("", rate, t);
00236         }
00237         else if(driver == 1)
00238         {
00239                 if(!rtabmap::CameraOpenNI2::available())
00240                 {
00241                         UERROR("Not built with OpenNI2 support...");
00242                         exit(-1);
00243                 }
00244                 camera = new rtabmap::CameraOpenNI2("", rate, t);
00245         }
00246         else if(driver == 2)
00247         {
00248                 if(!rtabmap::CameraFreenect::available())
00249                 {
00250                         UERROR("Not built with Freenect support...");
00251                         exit(-1);
00252                 }
00253                 camera = new rtabmap::CameraFreenect(0, rate, t);
00254         }
00255         else if(driver == 3)
00256         {
00257                 if(!rtabmap::CameraOpenNICV::available())
00258                 {
00259                         UERROR("Not built with OpenNI from OpenCV support...");
00260                         exit(-1);
00261                 }
00262                 camera = new rtabmap::CameraOpenNICV(false, rate, t);
00263         }
00264         else if(driver == 4)
00265         {
00266                 if(!rtabmap::CameraOpenNICV::available())
00267                 {
00268                         UERROR("Not built with OpenNI from OpenCV support...");
00269                         exit(-1);
00270                 }
00271                 camera = new rtabmap::CameraOpenNICV(true, rate, t);
00272         }
00273         else if(driver == 5)
00274         {
00275                 if(!rtabmap::CameraFreenect2::available())
00276                 {
00277                         UERROR("Not built with Freenect2 support...");
00278                         exit(-1);
00279                 }
00280                 camera = new rtabmap::CameraFreenect2(0, rtabmap::CameraFreenect2::kTypeColor2DepthSD, rate, t);
00281         }
00282         else if(driver == 6)
00283         {
00284                 if(!rtabmap::CameraStereoDC1394::available())
00285                 {
00286                         UERROR("Not built with dc1394 support...");
00287                         exit(-1);
00288                 }
00289                 camera = new rtabmap::CameraStereoDC1394(rate, t);
00290         }
00291         else if(driver == 7)
00292         {
00293                 if(!rtabmap::CameraStereoFlyCapture2::available())
00294                 {
00295                         UERROR("Not built with FlyCapture2/Triclops support...");
00296                         exit(-1);
00297                 }
00298                 camera = new rtabmap::CameraStereoFlyCapture2(rate, t);
00299         }
00300         else
00301         {
00302                 UFATAL("Camera driver (%d) not found!", driver);
00303         }
00304 
00305         //pcl::console::setVerbosityLevel(pcl::console::L_DEBUG);
00306 
00307         if(camera->init())
00308         {
00309                 if(camera->isCalibrated())
00310                 {
00311                         rtabmap::CameraThread cameraThread(camera, parameters);
00312 
00313                         cameraThread.setScanFromDepth(icp, decimation<1?1:decimation, maxDepth, voxelSize, normalsK);
00314 
00315                         odomThread.start();
00316                         cameraThread.start();
00317 
00318                         odomViewer.exec();
00319 
00320                         cameraThread.join(true);
00321                         odomThread.join(true);
00322                 }
00323                 else
00324                 {
00325                         printf("The camera is not calibrated! You should calibrate the camera first.\n");
00326                         delete camera;
00327                 }
00328         }
00329         else
00330         {
00331                 printf("Failed to initialize the camera! Please select another driver (see \"--help\").\n");
00332                 delete camera;
00333         }
00334 
00335         return 0;
00336 }


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