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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Sun Jul 24 2016 03:49:07