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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49