map_merger_node.cpp
Go to the documentation of this file.
00001 /* +---------------------------------------------------------------------------+
00002    |                     Mobile Robot Programming Toolkit (MRPT)               |
00003    |                          http://www.mrpt.org/                             |
00004    |                                                                           |
00005    | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file        |
00006    | See: http://www.mrpt.org/Authors - All rights reserved.                   |
00007    | Released under BSD License. See details in http://www.mrpt.org/License    |
00008    +---------------------------------------------------------------------------+ */
00009 
00010 #include <nav_msgs/OccupancyGrid.h>
00011 #include <nav_msgs/Path.h>
00012 #include <mrpt_msgs/GraphSlamAgents.h>
00013 #include <mrpt/utils/COutputLogger.h>
00014 #include <mrpt/maps/COccupancyGridMap2D.h>
00015 #include <mrpt_bridge/map.h>
00016 #include "mrpt_graphslam_2d/CMapMerger.h"
00017 #include "mrpt_graphslam_2d/TNeighborAgentMapProps.h"
00018 
00019 using namespace mrpt::graphslam;
00020 using namespace mrpt::graphslam::detail;
00021 using namespace mrpt_msgs;
00022 using namespace mrpt::maps;
00023 using namespace ros;
00024 using namespace mrpt::utils;
00025 using namespace nav_msgs;
00026 using namespace std;
00027 
00028 
00029 
00037 int main(int argc, char **argv)
00038 {
00039         // init ROS Node
00040         std::string node_name = "map_merger";
00041   ros::init(argc, argv, node_name);
00042         ros::NodeHandle nh;
00043         ros::Rate loop_rate(10);
00044 
00045         // initialize logger.
00046         COutputLogger logger;
00047         logger.setLoggerName(node_name);
00048         logger.setMinLoggingLevel(LVL_DEBUG);
00049         logger.logFmt(LVL_WARN, "Initialized %s node...\n", node_name.c_str());
00050 
00051         CMapMerger map_merger(&logger, &nh);
00052 
00053         bool continue_exec = true;
00054         while (ros::ok() && continue_exec) {
00055                 continue_exec = map_merger.updateState();
00056                 ros::spinOnce();
00057                 loop_rate.sleep();
00058         }
00059 
00060         return 0;
00061 }


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sun Sep 17 2017 03:02:04