Class responsible of the execution of the map_merger_node. More...
#include <CMapMerger.h>
Public Types | |
typedef std::map < TNeighborAgentMapProps *, COccupancyGridMap2D::Ptr > | maps_t |
typedef std::map < TNeighborAgentMapProps *, bool > | neighbor_to_is_used_t |
typedef std::map < TNeighborAgentMapProps *, mrpt::poses::CPose2D > | neighbor_to_rel_pose_t |
typedef std::vector < TNeighborAgentMapProps * > | neighbors_t |
typedef std::map < TNeighborAgentMapProps *, mrpt::opengl::CSetOfLines::Ptr > | trajectories_t |
Robot trajectory visual object type. | |
Public Member Functions | |
CMapMerger (mrpt::utils::COutputLogger *logger_in, ros::NodeHandle *nh_in) | |
void | mergeMaps () |
bool | updateState () |
Query and fetch the list of new graphSLAM agents. | |
~CMapMerger () | |
Private Member Functions | |
void | initWindowVisuals (mrpt::graphslam::CWindowManager *win_manager) |
mrpt::graphslam::CWindowManager * | initWindowVisuals () |
void | monitorKeystrokes (mrpt::graphslam::CWindowObserver *win_observer) |
Compact method for monitoring the given keystrokes for the given observer. | |
Private Attributes | |
mrpt::slam::CGridMapAligner::TConfigParams | m_alignment_options |
mrpt::graphslam::detail::CConnectionManager | m_conn_manager |
std::string | m_feedback_ns |
mrpt::graphslam::CWindowManager * | m_fused_map_win_manager |
std::string | m_global_ns |
Topic namespace under which current node is going to be publishing. | |
mrpt::utils::COutputLogger * | m_logger |
neighbors_t | m_neighbors |
CConnectionManager instance for fetching the running graphSLAM agents. | |
std::map < TNeighborAgentMapProps *, CWindowManager * > | m_neighbors_to_windows |
ros::NodeHandle * | m_nh |
std::string | m_options_ns |
Topic namespace under which, options that are used during the map alignment procedure are fetched from. | |
size_t | m_queue_size |
std::string | map_merge_keypress |
std::string | quit_keypress1 |
std::string | quit_keypress2 |
bool | save_map_merging_results |
Class responsible of the execution of the map_merger_node.
Instance of the graph asks of the generated maps of all the running GraphSlamAgents computes a feasible map-merging, if any, and returns the resulting global map to the user.
Definition at line 58 of file CMapMerger.h.
typedef std::map<TNeighborAgentMapProps*, COccupancyGridMap2D::Ptr> mrpt::graphslam::CMapMerger::maps_t |
Definition at line 61 of file CMapMerger.h.
typedef std::map<TNeighborAgentMapProps*, bool> mrpt::graphslam::CMapMerger::neighbor_to_is_used_t |
Definition at line 62 of file CMapMerger.h.
typedef std::map<TNeighborAgentMapProps*, mrpt::poses::CPose2D> mrpt::graphslam::CMapMerger::neighbor_to_rel_pose_t |
Definition at line 63 of file CMapMerger.h.
typedef std::vector<TNeighborAgentMapProps*> mrpt::graphslam::CMapMerger::neighbors_t |
Definition at line 69 of file CMapMerger.h.
typedef std::map< TNeighborAgentMapProps*, mrpt::opengl::CSetOfLines::Ptr> mrpt::graphslam::CMapMerger::trajectories_t |
Robot trajectory visual object type.
Definition at line 68 of file CMapMerger.h.
CMapMerger::CMapMerger | ( | mrpt::utils::COutputLogger * | logger_in, |
ros::NodeHandle * | nh_in | ||
) |
Definition at line 128 of file CMapMerger.cpp.
Definition at line 173 of file CMapMerger.cpp.
void CMapMerger::initWindowVisuals | ( | mrpt::graphslam::CWindowManager * | win_manager | ) | [private] |
Definition at line 586 of file CMapMerger.cpp.
CWindowManager * CMapMerger::initWindowVisuals | ( | ) | [private] |
Definition at line 580 of file CMapMerger.cpp.
void CMapMerger::mergeMaps | ( | ) |
Definition at line 281 of file CMapMerger.cpp.
void CMapMerger::monitorKeystrokes | ( | mrpt::graphslam::CWindowObserver * | win_observer | ) | [private] |
Compact method for monitoring the given keystrokes for the given observer.
Definition at line 162 of file CMapMerger.cpp.
bool CMapMerger::updateState | ( | ) |
Query and fetch the list of new graphSLAM agents.
Definition at line 194 of file CMapMerger.cpp.
mrpt::slam::CGridMapAligner::TConfigParams mrpt::graphslam::CMapMerger::m_alignment_options [private] |
Definition at line 106 of file CMapMerger.h.
Definition at line 95 of file CMapMerger.h.
std::string mrpt::graphslam::CMapMerger::m_feedback_ns [private] |
Definition at line 104 of file CMapMerger.h.
mrpt::graphslam::CWindowManager* mrpt::graphslam::CMapMerger::m_fused_map_win_manager [private] |
Definition at line 114 of file CMapMerger.h.
std::string mrpt::graphslam::CMapMerger::m_global_ns [private] |
Topic namespace under which current node is going to be publishing.
Definition at line 99 of file CMapMerger.h.
mrpt::utils::COutputLogger* mrpt::graphslam::CMapMerger::m_logger [private] |
Definition at line 93 of file CMapMerger.h.
CConnectionManager instance for fetching the running graphSLAM agents.
Definition at line 91 of file CMapMerger.h.
std::map<TNeighborAgentMapProps*, CWindowManager*> mrpt::graphslam::CMapMerger::m_neighbors_to_windows [private] |
Definition at line 92 of file CMapMerger.h.
ros::NodeHandle* mrpt::graphslam::CMapMerger::m_nh [private] |
Definition at line 94 of file CMapMerger.h.
std::string mrpt::graphslam::CMapMerger::m_options_ns [private] |
Topic namespace under which, options that are used during the map alignment procedure are fetched from.
Definition at line 103 of file CMapMerger.h.
size_t mrpt::graphslam::CMapMerger::m_queue_size [private] |
Definition at line 105 of file CMapMerger.h.
std::string mrpt::graphslam::CMapMerger::map_merge_keypress [private] |
Definition at line 110 of file CMapMerger.h.
std::string mrpt::graphslam::CMapMerger::quit_keypress1 [private] |
Definition at line 108 of file CMapMerger.h.
std::string mrpt::graphslam::CMapMerger::quit_keypress2 [private] |
Definition at line 109 of file CMapMerger.h.
bool mrpt::graphslam::CMapMerger::save_map_merging_results [private] |
Definition at line 112 of file CMapMerger.h.