CoreNode.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "ros/ros.h"
32 #include <rtabmap/utilite/UStl.h>
33 #include <rtabmap/utilite/UFile.h>
34 #include <rtabmap/core/Version.h>
35 #include "nodelet/loader.h"
36 
37 int main(int argc, char** argv)
38 {
39  ROS_INFO("Starting node...");
40 
43 
44  ros::init(argc, argv, "rtabmap");
45 
46  nodelet::V_string nargv;
47  for(int i=1;i<argc;++i)
48  {
49  if(strcmp(argv[i], "--params") == 0 || strcmp(argv[i], "--params-all") == 0)
50  {
52  uInsert(parameters, rtabmap::ParametersPair(rtabmap::Parameters::kRGBDCreateOccupancyGrid(), "true")); // default true in ROS
53  char * rosHomePath = getenv("ROS_HOME");
54  std::string workingDir = rosHomePath?rosHomePath:UDirectory::homeDir()+"/.ros";
55  uInsert(parameters, rtabmap::ParametersPair(rtabmap::Parameters::kRtabmapWorkingDirectory(), workingDir)); // change default to ~/.ros
56 
57  if(strcmp(argv[i], "--params") == 0)
58  {
59  // hide specific parameters
60  for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end();)
61  {
62  if(iter->first.find("Odom") == 0)
63  {
64  parameters.erase(iter++);
65  }
66  else
67  {
68  ++iter;
69  }
70  }
71  }
72 
73  for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
74  {
75  std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
76  std::cout <<
77  str <<
78  std::setw(60 - str.size()) <<
79  " [" <<
80  rtabmap::Parameters::getDescription(iter->first).c_str() <<
81  "]" <<
82  std::endl;
83  }
84  ROS_WARN("Node will now exit after showing default RTAB-Map parameters because "
85  "argument \"--params\" is detected!");
86  exit(0);
87  }
88  nargv.push_back(argv[i]);
89  }
90 
93  std::string nodelet_name = ros::this_node::getName();
94  nodelet.load(nodelet_name, "rtabmap_slam/rtabmap", remap, nargv);
95  ROS_INFO("rtabmap %s started...", RTABMAP_VERSION);
96  ros::spin();
97 
98  return 0;
99 }
nodelet::V_string
std::vector< std::string > V_string
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
nodelet::M_string
std::map< std::string, std::string > M_string
loader.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ULogger::kTypeConsole
kTypeConsole
ros.h
ULogger::setLevel
static void setLevel(ULogger::Level level)
UStl.h
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
nodelet::Loader
UDirectory::homeDir
static std::string homeDir()
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
uInsert
void uInsert(std::map< K, V > &map, const std::map< K, V > &items)
ULogger::kWarning
kWarning
ros::names::getRemappings
const ROSCPP_DECL M_string & getRemappings()
argv
argv
UDirectory.h
ROS_WARN
#define ROS_WARN(...)
ULogger::setType
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
remap
ROSCPP_DECL std::string remap(const std::string &name)
str
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
nodelet
UFile.h
iter
iterator iter(handle obj)
ULogger.h
Parameters.h
ros::spin
ROSCPP_DECL void spin()
ROS_INFO
#define ROS_INFO(...)
main
int main(int argc, char **argv)
Definition: CoreNode.cpp:37
i
int i
rtabmap::Parameters::getDescription
static std::string getDescription(const std::string &paramKey)


rtabmap_slam
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:43:58