Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
mrpt::graphslam::CMapMerger Class Reference

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. More...
 

Public Member Functions

 CMapMerger (mrpt::system::COutputLogger *logger_in, ros::NodeHandle *nh_in)
 
void mergeMaps ()
 
bool updateState ()
 Query and fetch the list of new graphSLAM agents. More...
 
 ~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. More...
 

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. More...
 
mrpt::system::COutputLogger * m_logger
 
neighbors_t m_neighbors
 CConnectionManager instance for fetching the running graphSLAM agents. More...
 
std::map< TNeighborAgentMapProps *, CWindowManager * > m_neighbors_to_windows
 
ros::NodeHandlem_nh
 
std::string m_options_ns
 Topic namespace under which, options that are used during the map alignment procedure are fetched from. More...
 
size_t m_queue_size
 
std::string map_merge_keypress
 
std::string quit_keypress1
 
std::string quit_keypress2
 
bool save_map_merging_results
 

Detailed Description

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 54 of file CMapMerger.h.

Member Typedef Documentation

◆ maps_t

typedef std::map<TNeighborAgentMapProps*, COccupancyGridMap2D::Ptr> mrpt::graphslam::CMapMerger::maps_t

Definition at line 57 of file CMapMerger.h.

◆ neighbor_to_is_used_t

Definition at line 58 of file CMapMerger.h.

◆ neighbor_to_rel_pose_t

Definition at line 60 of file CMapMerger.h.

◆ neighbors_t

Definition at line 65 of file CMapMerger.h.

◆ trajectories_t

typedef std::map<TNeighborAgentMapProps*, mrpt::opengl::CSetOfLines::Ptr> mrpt::graphslam::CMapMerger::trajectories_t

Robot trajectory visual object type.

Definition at line 64 of file CMapMerger.h.

Constructor & Destructor Documentation

◆ CMapMerger()

CMapMerger::CMapMerger ( mrpt::system::COutputLogger *  logger_in,
ros::NodeHandle nh_in 
)

options.methodSelection = CGridMapAligner::amRobustMatch; // ASSERTION ERROR

Definition at line 136 of file CMapMerger.cpp.

◆ ~CMapMerger()

CMapMerger::~CMapMerger ( )

Definition at line 179 of file CMapMerger.cpp.

Member Function Documentation

◆ initWindowVisuals() [1/2]

void CMapMerger::initWindowVisuals ( mrpt::graphslam::CWindowManager *  win_manager)
private

Definition at line 631 of file CMapMerger.cpp.

◆ initWindowVisuals() [2/2]

CWindowManager * CMapMerger::initWindowVisuals ( )
private

Definition at line 624 of file CMapMerger.cpp.

◆ mergeMaps()

void CMapMerger::mergeMaps ( )

Definition at line 290 of file CMapMerger.cpp.

◆ monitorKeystrokes()

void CMapMerger::monitorKeystrokes ( mrpt::graphslam::CWindowObserver *  win_observer)
private

Compact method for monitoring the given keystrokes for the given observer.

Definition at line 169 of file CMapMerger.cpp.

◆ updateState()

bool CMapMerger::updateState ( )

Query and fetch the list of new graphSLAM agents.

Returns
True if execution is to continue normally.

Definition at line 199 of file CMapMerger.cpp.

Member Data Documentation

◆ m_alignment_options

mrpt::slam::CGridMapAligner::TConfigParams mrpt::graphslam::CMapMerger::m_alignment_options
private

Definition at line 102 of file CMapMerger.h.

◆ m_conn_manager

mrpt::graphslam::detail::CConnectionManager mrpt::graphslam::CMapMerger::m_conn_manager
private

Definition at line 90 of file CMapMerger.h.

◆ m_feedback_ns

std::string mrpt::graphslam::CMapMerger::m_feedback_ns
private

Definition at line 100 of file CMapMerger.h.

◆ m_fused_map_win_manager

mrpt::graphslam::CWindowManager* mrpt::graphslam::CMapMerger::m_fused_map_win_manager
private

Definition at line 110 of file CMapMerger.h.

◆ m_global_ns

std::string mrpt::graphslam::CMapMerger::m_global_ns
private

Topic namespace under which current node is going to be publishing.

Definition at line 95 of file CMapMerger.h.

◆ m_logger

mrpt::system::COutputLogger* mrpt::graphslam::CMapMerger::m_logger
private

Definition at line 88 of file CMapMerger.h.

◆ m_neighbors

neighbors_t mrpt::graphslam::CMapMerger::m_neighbors
private

CConnectionManager instance for fetching the running graphSLAM agents.

Definition at line 86 of file CMapMerger.h.

◆ m_neighbors_to_windows

std::map<TNeighborAgentMapProps*, CWindowManager*> mrpt::graphslam::CMapMerger::m_neighbors_to_windows
private

Definition at line 87 of file CMapMerger.h.

◆ m_nh

ros::NodeHandle* mrpt::graphslam::CMapMerger::m_nh
private

Definition at line 89 of file CMapMerger.h.

◆ m_options_ns

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 99 of file CMapMerger.h.

◆ m_queue_size

size_t mrpt::graphslam::CMapMerger::m_queue_size
private

Definition at line 101 of file CMapMerger.h.

◆ map_merge_keypress

std::string mrpt::graphslam::CMapMerger::map_merge_keypress
private

Definition at line 106 of file CMapMerger.h.

◆ quit_keypress1

std::string mrpt::graphslam::CMapMerger::quit_keypress1
private

Definition at line 104 of file CMapMerger.h.

◆ quit_keypress2

std::string mrpt::graphslam::CMapMerger::quit_keypress2
private

Definition at line 105 of file CMapMerger.h.

◆ save_map_merging_results

bool mrpt::graphslam::CMapMerger::save_map_merging_results
private

Definition at line 108 of file CMapMerger.h.


The documentation for this class was generated from the following files:


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sun Jun 26 2022 02:12:26