Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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"));
00053 uInsert(parameters, rtabmap::ParametersPair(rtabmap::Parameters::kRtabmapWorkingDirectory(), UDirectory::homeDir()+"/.ros"));
00054
00055 if(strcmp(argv[i], "--params") == 0)
00056 {
00057
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 }