CMapMerger.h
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 #pragma once
12 
16 
17 #include <ros/ros.h>
18 #include <nav_msgs/OccupancyGrid.h>
19 #include <nav_msgs/Path.h>
20 #include <mrpt_msgs/GraphSlamAgents.h>
21 #include <mrpt/maps/COccupancyGridMap2D.h>
22 #include <mrpt/maps/CSimplePointsMap.h>
23 #include <mrpt/slam/CGridMapAligner.h>
24 #include <mrpt/ros1bridge/map.h>
25 #include <mrpt/system/filesystem.h>
26 #include <mrpt/system/os.h>
27 #include <mrpt/math/utils.h>
28 #include <mrpt/graphslam/misc/CWindowManager.h>
29 #include <mrpt/opengl/CAxis.h>
30 #include <mrpt/opengl/CGridPlaneXY.h>
31 #include <mrpt/opengl/CSetOfLines.h>
32 #include <mrpt/opengl/COpenGLScene.h>
33 #include <mrpt/system/COutputLogger.h>
34 #include <mrpt/img/TColorManager.h>
35 
36 #include <iterator>
37 
38 const mrpt::poses::CPose3D EMPTY_POSE;
39 
40 using namespace mrpt::system;
41 using namespace mrpt::img;
42 using namespace mrpt::maps;
43 using namespace mrpt::obs;
44 
45 namespace mrpt
46 {
47 namespace graphslam
48 {
56 {
57  public:
58  typedef std::map<TNeighborAgentMapProps*, COccupancyGridMap2D::Ptr> maps_t;
59  typedef std::map<TNeighborAgentMapProps*, bool> neighbor_to_is_used_t;
60  typedef std::map<TNeighborAgentMapProps*, mrpt::poses::CPose2D>
62 
64  typedef std::map<TNeighborAgentMapProps*, mrpt::opengl::CSetOfLines::Ptr>
66  typedef std::vector<TNeighborAgentMapProps*> neighbors_t;
67  CMapMerger(mrpt::system::COutputLogger* logger_in, ros::NodeHandle* nh_in);
68  ~CMapMerger();
69  void mergeMaps();
74  bool updateState();
75 
76  private:
80  void monitorKeystrokes(mrpt::graphslam::CWindowObserver* win_observer);
81  void initWindowVisuals(mrpt::graphslam::CWindowManager* win_manager);
82  mrpt::graphslam::CWindowManager* initWindowVisuals();
83 
88  std::map<TNeighborAgentMapProps*, CWindowManager*> m_neighbors_to_windows;
89  mrpt::system::COutputLogger* m_logger;
92 
96  std::string m_global_ns;
100  std::string m_options_ns;
101  std::string m_feedback_ns;
102  size_t m_queue_size;
103  mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options;
104 
105  std::string quit_keypress1;
106  std::string quit_keypress2;
107  std::string map_merge_keypress;
108 
110 
111  mrpt::graphslam::CWindowManager* m_fused_map_win_manager;
112 
113 }; // end of CMapMerger
114 
115 } // namespace graphslam
116 } // namespace mrpt
mrpt::graphslam::CMapMerger::trajectories_t
std::map< TNeighborAgentMapProps *, mrpt::opengl::CSetOfLines::Ptr > trajectories_t
Robot trajectory visual object type.
Definition: CMapMerger.h:65
mrpt::graphslam::CMapMerger::maps_t
std::map< TNeighborAgentMapProps *, COccupancyGridMap2D::Ptr > maps_t
Definition: CMapMerger.h:58
CConnectionManager.h
mrpt::graphslam::CMapMerger::m_logger
mrpt::system::COutputLogger * m_logger
Definition: CMapMerger.h:89
mrpt::graphslam::CMapMerger::m_global_ns
std::string m_global_ns
Topic namespace under which current node is going to be publishing.
Definition: CMapMerger.h:96
mrpt::graphslam::CMapMerger::m_options_ns
std::string m_options_ns
Topic namespace under which, options that are used during the map alignment procedure are fetched fro...
Definition: CMapMerger.h:100
ros.h
mrpt::graphslam::CMapMerger::m_queue_size
size_t m_queue_size
Definition: CMapMerger.h:102
mrpt::graphslam::CMapMerger::neighbor_to_is_used_t
std::map< TNeighborAgentMapProps *, bool > neighbor_to_is_used_t
Definition: CMapMerger.h:59
mrpt::graphslam::CMapMerger::m_conn_manager
mrpt::graphslam::detail::CConnectionManager m_conn_manager
Definition: CMapMerger.h:91
mrpt::graphslam::CMapMerger::save_map_merging_results
bool save_map_merging_results
Definition: CMapMerger.h:109
EMPTY_POSE
const mrpt::poses::CPose3D EMPTY_POSE
Definition: CMapMerger.h:38
mrpt::graphslam::CMapMerger::neighbors_t
std::vector< TNeighborAgentMapProps * > neighbors_t
Definition: CMapMerger.h:66
mrpt
Definition: CConnectionManager.h:31
mrpt::graphslam::CMapMerger::map_merge_keypress
std::string map_merge_keypress
Definition: CMapMerger.h:107
TNeighborAgentMapProps.h
mrpt::graphslam::detail::CConnectionManager
Class responsible of handling the network communication between SLAM agents in the Multi-Robot graphS...
Definition: CConnectionManager.h:40
mrpt::graphslam::CMapMerger::m_neighbors_to_windows
std::map< TNeighborAgentMapProps *, CWindowManager * > m_neighbors_to_windows
Definition: CMapMerger.h:88
mrpt::graphslam::CMapMerger
Class responsible of the execution of the map_merger_node.
Definition: CMapMerger.h:55
mrpt::graphslam::CMapMerger::quit_keypress2
std::string quit_keypress2
Definition: CMapMerger.h:106
mrpt::graphslam::CMapMerger::m_fused_map_win_manager
mrpt::graphslam::CWindowManager * m_fused_map_win_manager
Definition: CMapMerger.h:111
mrpt::graphslam::CMapMerger::quit_keypress1
std::string quit_keypress1
Definition: CMapMerger.h:105
mrpt::graphslam::CMapMerger::m_alignment_options
mrpt::slam::CGridMapAligner::TConfigParams m_alignment_options
Definition: CMapMerger.h:103
common.h
mrpt::graphslam::CMapMerger::neighbor_to_rel_pose_t
std::map< TNeighborAgentMapProps *, mrpt::poses::CPose2D > neighbor_to_rel_pose_t
Definition: CMapMerger.h:61
mrpt::graphslam::CMapMerger::m_neighbors
neighbors_t m_neighbors
CConnectionManager instance for fetching the running graphSLAM agents.
Definition: CMapMerger.h:87
mrpt::graphslam::CMapMerger::m_nh
ros::NodeHandle * m_nh
Definition: CMapMerger.h:90
ros::NodeHandle
mrpt::graphslam::CMapMerger::m_feedback_ns
std::string m_feedback_ns
Definition: CMapMerger.h:101


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Sep 19 2024 02:26:31