map_merger_node.cpp
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 
10 #include <nav_msgs/OccupancyGrid.h>
11 #include <nav_msgs/Path.h>
12 #include <mrpt_msgs/GraphSlamAgents.h>
14 #include <mrpt/maps/COccupancyGridMap2D.h>
15 #include <mrpt_bridge/map.h>
18 
19 using namespace mrpt::graphslam;
20 using namespace mrpt::graphslam::detail;
21 using namespace mrpt_msgs;
22 using namespace mrpt::maps;
23 using namespace ros;
24 using namespace mrpt::utils;
25 using namespace nav_msgs;
26 using namespace std;
27 
28 
29 
37 int main(int argc, char **argv)
38 {
39  // init ROS Node
40  std::string node_name = "map_merger";
41  ros::init(argc, argv, node_name);
42  ros::NodeHandle nh;
43  ros::Rate loop_rate(10);
44 
45  // initialize logger.
46  COutputLogger logger;
47  logger.setLoggerName(node_name);
48  logger.setMinLoggingLevel(LVL_DEBUG);
49  logger.logFmt(LVL_WARN, "Initialized %s node...\n", node_name.c_str());
50 
51  CMapMerger map_merger(&logger, &nh);
52 
53  bool continue_exec = true;
54  while (ros::ok() && continue_exec) {
55  continue_exec = map_merger.updateState();
56  ros::spinOnce();
57  loop_rate.sleep();
58  }
59 
60  return 0;
61 }
Class responsible of the execution of the map_merger_node.
Definition: CMapMerger.h:58
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Node that fetches the local maps produced by the graphSLAM agents and joins them together using a RAN...
ROSCPP_DECL bool ok()
bool sleep()
bool updateState()
Query and fetch the list of new graphSLAM agents.
Definition: CMapMerger.cpp:194
ROSCPP_DECL void spinOnce()


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sat May 2 2020 03:44:17