34 #include <rtabmap/core/Version.h> 37 int main(
int argc,
char** argv)
47 for(
int i=1;i<argc;++i)
49 if(strcmp(argv[i],
"--params") == 0 || strcmp(argv[i],
"--params-all") == 0)
55 if(strcmp(argv[i],
"--params") == 0)
58 for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end();)
60 if(iter->first.find(
"Odom") == 0)
62 parameters.erase(iter++);
71 for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
73 std::string str =
"Param: " + iter->first +
" = \"" + iter->second +
"\"";
76 std::setw(60 - str.size()) <<
82 ROS_WARN(
"Node will now exit after showing default RTAB-Map parameters because " 83 "argument \"--params\" is detected!");
86 nargv.push_back(argv[i]);
92 nodelet.
load(nodelet_name,
"rtabmap_ros/rtabmap", remap, nargv);
93 ROS_INFO(
"rtabmap %s started...", RTABMAP_VERSION);
static std::string homeDir()
static std::string getDescription(const std::string ¶mKey)
bool load(const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv)
std::pair< std::string, std::string > ParametersPair
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::map< std::string, std::string > ParametersMap
ROSCPP_DECL const std::string & getName()
static void setLevel(ULogger::Level level)
ROSCPP_DECL void spin(Spinner &spinner)
ROSCPP_DECL const M_string & getRemappings()
ROSCPP_DECL std::string remap(const std::string &name)
int main(int argc, char **argv)
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
static const ParametersMap & getDefaultParameters()
std::vector< std::string > V_string
std::map< std::string, std::string > M_string
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)