CoreNode.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 "CoreWrapper.h"
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <rtabmap/utilite/UDirectory.h>
00031 #include <rtabmap/utilite/UStl.h>
00032 #include <rtabmap/utilite/UFile.h>
00033 
00034 int main(int argc, char** argv)
00035 {
00036         ROS_INFO("Starting node...");
00037 
00038         ULogger::setType(ULogger::kTypeConsole);
00039         ULogger::setLevel(ULogger::kWarning);
00040 
00041         ros::init(argc, argv, "rtabmap");
00042 
00043         bool deleteDbOnStart = false;
00044         for(int i=1;i<argc;++i)
00045         {
00046                 if(strcmp(argv[i], "--delete_db_on_start") == 0)
00047                 {
00048                         deleteDbOnStart = true;
00049                 }
00050                 else if(strcmp(argv[i], "--udebug") == 0)
00051                 {
00052                         ULogger::setLevel(ULogger::kDebug);
00053                 }
00054                 else if(strcmp(argv[i], "--uinfo") == 0)
00055                 {
00056                         ULogger::setLevel(ULogger::kInfo);
00057                 }
00058                 else if(strcmp(argv[i], "--params") == 0 || strcmp(argv[i], "--params-all") == 0)
00059                 {
00060                         rtabmap::ParametersMap parameters = rtabmap::Parameters::getDefaultParameters();
00061                         uInsert(parameters,
00062                                         std::make_pair(rtabmap::Parameters::kRtabmapWorkingDirectory(),
00063                                         UDirectory::homeDir()+"/.ros")); // change default to ~/.ros
00064 
00065                         if(strcmp(argv[i], "--params") == 0)
00066                         {
00067                                 // hide specific parameters
00068                                 for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end();)
00069                                 {
00070                                         if(iter->first.find("Odom") == 0)
00071                                         {
00072                                                 parameters.erase(iter++);
00073                                         }
00074                                         else
00075                                         {
00076                                                 ++iter;
00077                                         }
00078                                 }
00079                         }
00080 
00081                         for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00082                         {
00083                                 std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
00084                                 std::cout <<
00085                                                 str <<
00086                                                 std::setw(60 - str.size()) <<
00087                                                 " [" <<
00088                                                 rtabmap::Parameters::getDescription(iter->first).c_str() <<
00089                                                 "]" <<
00090                                                 std::endl;
00091                         }
00092                         ROS_WARN("Node will now exit after showing default RTAB-Map parameters because "
00093                                          "argument \"--params\" is detected!");
00094                         exit(0);
00095                 }
00096                 else
00097                 {
00098                         ROS_ERROR("Not recognized argument \"%s\"", argv[i]);
00099                         exit(-1);
00100                 }
00101         }
00102 
00103         CoreWrapper * rtabmap = new CoreWrapper(deleteDbOnStart);
00104 
00105         ROS_INFO("rtabmap started...");
00106         ros::spin();
00107 
00108         delete rtabmap;
00109 
00110         return 0;
00111 }


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:24