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  uInsert(parameters, rtabmap::ParametersPair(rtabmap::Parameters::kRtabmapWorkingDirectory(), UDirectory::homeDir()+"/.ros")); // change default to ~/.ros
54 
55  if(strcmp(argv[i], "--params") == 0)
56  {
57  // hide specific parameters
58  for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end();)
59  {
60  if(iter->first.find("Odom") == 0)
61  {
62  parameters.erase(iter++);
63  }
64  else
65  {
66  ++iter;
67  }
68  }
69  }
70 
71  for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
72  {
73  std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
74  std::cout <<
75  str <<
76  std::setw(60 - str.size()) <<
77  " [" <<
78  rtabmap::Parameters::getDescription(iter->first).c_str() <<
79  "]" <<
80  std::endl;
81  }
82  ROS_WARN("Node will now exit after showing default RTAB-Map parameters because "
83  "argument \"--params\" is detected!");
84  exit(0);
85  }
86  nargv.push_back(argv[i]);
87  }
88 
91  std::string nodelet_name = ros::this_node::getName();
92  nodelet.load(nodelet_name, "rtabmap_ros/rtabmap", remap, nargv);
93  ROS_INFO("rtabmap %s started...", RTABMAP_VERSION);
94  ros::spin();
95 
96  return 0;
97 }
static std::string homeDir()
static std::string getDescription(const std::string &paramKey)
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)
#define ROS_WARN(...)
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)
Definition: CoreNode.cpp:37
#define ROS_INFO(...)
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)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:03