Public Types | Public Member Functions | Public Attributes | List of all members
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions Struct Reference
Inheritance diagram for mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions:
Inheritance graph
[legend]

Public Types

typedef self_t engine_mr_t
 

Public Member Functions

void dumpToTextStream (mrpt::utils::CStream &out) const
 
void loadFromConfigFile (const CConfigFileBase &source, const std::string &section)
 
 TOptions (const engine_mr_t &engine_in)
 
 ~TOptions ()
 

Public Attributes

bool conservative_find_initial_tfs_to_neighbors
 Be conservative when it comes to deciding the initial transformation of own graph with regards to graphs of the neighboring agents. If true engine won't use map merging but instead will be waiting for rendez-vous with other agents to determine the tf. More...
 
const engine_mr_tengine
 
size_t inter_group_node_count_thresh
 Lowest number of nodes that should exist in a group of nodes before evaluating it. These nodes are fetched by the other running graphSLAM agents. More...
 
size_t inter_group_node_count_thresh_minadv
 Minimum advised limit of inter_group_node_count_thresh. More...
 
int nodes_integration_batch_size
 After an inter-graph transformation is found between own graph and a neighbor's map, newly fetched neighbor's nodes are added in batches. More...
 
int num_last_regd_nodes
 Max number of last registered NodeIDs + corresponding positions to publish. More...
 

Detailed Description

template<class GRAPH_T>
struct mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions

Definition at line 519 of file CGraphSlamEngine_MR.h.

Member Typedef Documentation

template<class GRAPH_T>
typedef self_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::engine_mr_t

Definition at line 521 of file CGraphSlamEngine_MR.h.

Constructor & Destructor Documentation

template<class GRAPH_T >
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::TOptions ( const engine_mr_t engine_in)

Definition at line 1445 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::~TOptions ( )

Definition at line 1456 of file CGraphSlamEngine_MR_impl.h.

Member Function Documentation

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::dumpToTextStream ( mrpt::utils::CStream &  out) const

Definition at line 1488 of file CGraphSlamEngine_MR_impl.h.

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::loadFromConfigFile ( const CConfigFileBase &  source,
const std::string &  section 
)

Definition at line 1460 of file CGraphSlamEngine_MR_impl.h.

Member Data Documentation

template<class GRAPH_T>
bool mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::conservative_find_initial_tfs_to_neighbors

Be conservative when it comes to deciding the initial transformation of own graph with regards to graphs of the neighboring agents. If true engine won't use map merging but instead will be waiting for rendez-vous with other agents to determine the tf.

Warning
Rendez-vous behavior is not yet implemented.

Definition at line 542 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
const engine_mr_t& mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::engine

Instance of engine which uses this struct

Definition at line 567 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
size_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::inter_group_node_count_thresh

Lowest number of nodes that should exist in a group of nodes before evaluating it. These nodes are fetched by the other running graphSLAM agents.

Note
This should be set >= 3
See also
inter_group_node_count_thresh_minadv

Definition at line 560 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
size_t mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::inter_group_node_count_thresh_minadv

Minimum advised limit of inter_group_node_count_thresh.

See also
inter_group_node_count_thresh

Definition at line 564 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
int mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::nodes_integration_batch_size

After an inter-graph transformation is found between own graph and a neighbor's map, newly fetched neighbor's nodes are added in batches.

Definition at line 546 of file CGraphSlamEngine_MR.h.

template<class GRAPH_T>
int mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >::TOptions::num_last_regd_nodes

Max number of last registered NodeIDs + corresponding positions to publish.

This is necessary for the other GraphSLAM agents so that they can use this information to localize the current agent in their own map and later make a querry for the Condensed Measurements Graph.

Definition at line 553 of file CGraphSlamEngine_MR.h.


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


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Jun 6 2019 19:37:48