src
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
11
#include <nav_msgs/OccupancyGrid.h>
12
#include <nav_msgs/Path.h>
13
#include <mrpt_msgs/GraphSlamAgents.h>
14
#include <mrpt/system/COutputLogger.h>
15
#include <mrpt/maps/COccupancyGridMap2D.h>
16
#include <mrpt/ros1bridge/map.h>
17
#include "
mrpt_graphslam_2d/CMapMerger.h
"
18
#include "
mrpt_graphslam_2d/TNeighborAgentMapProps.h
"
19
20
using namespace
mrpt::graphslam
;
21
using namespace
mrpt::graphslam::detail
;
22
using namespace
mrpt_msgs;
23
using namespace
mrpt::maps;
24
using namespace
ros
;
25
using namespace
nav_msgs;
26
using namespace
std
;
27
35
int
main
(
int
argc,
char
** argv)
36
{
37
// init ROS Node
38
std::string node_name =
"map_merger"
;
39
ros::init
(argc, argv, node_name);
40
ros::NodeHandle
nh;
41
ros::Rate
loop_rate(10);
42
43
// initialize logger.
44
COutputLogger
logger
;
45
logger
.setLoggerName(node_name);
46
logger
.setMinLoggingLevel(LVL_DEBUG);
47
logger
.logFmt(LVL_WARN,
"Initialized %s node...\n"
, node_name.c_str());
48
49
CMapMerger
map_merger(&
logger
, &nh);
50
51
bool
continue_exec =
true
;
52
while
(
ros::ok
() && continue_exec)
53
{
54
continue_exec = map_merger.
updateState
();
55
ros::spinOnce
();
56
loop_rate.
sleep
();
57
}
58
59
return
0;
60
}
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
main
int main(int argc, char **argv)
Node that fetches the local maps produced by the graphSLAM agents and joins them together using a RAN...
Definition:
map_merger_node.cpp:35
ros
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::ok
ROSCPP_DECL bool ok()
rename_rviz_topics.logger
logger
Definition:
rename_rviz_topics.py:31
TNeighborAgentMapProps.h
mrpt::graphslam::CMapMerger::updateState
bool updateState()
Query and fetch the list of new graphSLAM agents.
Definition:
CMapMerger.cpp:199
mrpt::graphslam
Definition:
CConnectionManager.h:33
mrpt::graphslam::CMapMerger
Class responsible of the execution of the map_merger_node.
Definition:
CMapMerger.h:55
CMapMerger.h
ros::Rate::sleep
bool sleep()
std
mrpt::graphslam::detail
Definition:
CConnectionManager.h:35
ros::Rate
ros::NodeHandle
mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Sep 19 2024 02:26:31