Public Member Functions | List of all members
mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T > Class Template Reference

#include <CLoopCloserERD_MR.h>

Inheritance diagram for mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >:
Inheritance graph
[legend]

Public Types

typedef CLoopCloserERD< GRAPH_T > lc_parent_t
 Handy typedefs. More...
 
typedef CEdgeRegistrationDecider_MR< GRAPH_T > mr_parent_t
 
typedef CLoopCloserERD_MR< GRAPH_T > decider_t
 
typedef lc_parent_t::constraint_t constraint_t
 
typedef lc_parent_t::pose_t pose_t
 
typedef lc_parent_t::range_ops_t range_ops_t
 
typedef lc_parent_t::partitions_t partitions_t
 
typedef lc_parent_t::nodes_to_scans2D_t nodes_to_scans2D_t
 
typedef mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T > engine_t
 
typedef GRAPH_T::global_pose_t global_pose_t
 
- Public Types inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer_MR< GRAPH_T >
typedef CGraphSlamEngine_MR< GRAPH_T > engine_t
 

Public Member Functions

void addBatchOfNodeIDsAndScans (const std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodeIDs_to_scans2D)
 
void addScanMatchingEdges (TNodeID curr_nodeID)
 
 CLoopCloserERD_MR ()
 
void fetchNodeIDsForScanMatching (const TNodeID &curr_nodeID, std::set< TNodeID > *nodes_set)
 
bool updateState (mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation)
 
- Public Member Functions inherited from mrpt::graphslam::deciders::CEdgeRegistrationDecider_MR< GRAPH_T >
 CEdgeRegistrationDecider_MR ()
 
 ~CEdgeRegistrationDecider_MR ()
 
- Public Member Functions inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer_MR< GRAPH_T >
 CRegistrationDeciderOrOptimizer_MR ()
 
virtual void setCConnectionManagerPtr (mrpt::graphslam::detail::CConnectionManager *conn_manager)
 
void setCGraphSlamEnginePtr (const engine_t *engine)
 
 ~CRegistrationDeciderOrOptimizer_MR ()
 
- Public Member Functions inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer_ROS< GRAPH_T >
 CRegistrationDeciderOrOptimizer_ROS ()
 
virtual void setNodeHandle (ros::NodeHandle *nh)
 
virtual ~CRegistrationDeciderOrOptimizer_ROS ()
 

Additional Inherited Members

- Protected Attributes inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer_MR< GRAPH_T >
mrpt::graphslam::detail::CConnectionManagerm_conn_manager
 Pointer to the CConnectionManager instance. More...
 
const engine_tm_engine
 Constant pointer to the CGraphSlamEngine_MR instance. More...
 
std::string own_ns
 
- Protected Attributes inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer_ROS< GRAPH_T >
ros::NodeHandlem_nh
 NodeHandle instance. More...
 

Detailed Description

template<class GRAPH_T>
class mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >

Loop Closer Edge Registration Decider class that can also be used in multi-robot SLAM operations since it can utilize information from other robot agents and correct own graph according to the strategy described in [1].

Note
Multi-robot-related classes are suffixed with _MR.

Definition at line 26 of file CLoopCloserERD_MR.h.

Member Typedef Documentation

template<class GRAPH_T >
typedef lc_parent_t::constraint_t mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::constraint_t

Definition at line 37 of file CLoopCloserERD_MR.h.

template<class GRAPH_T >
typedef CLoopCloserERD_MR<GRAPH_T> mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::decider_t

handy self type

Definition at line 36 of file CLoopCloserERD_MR.h.

Definition at line 42 of file CLoopCloserERD_MR.h.

template<class GRAPH_T >
typedef GRAPH_T::global_pose_t mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::global_pose_t

Definition at line 43 of file CLoopCloserERD_MR.h.

template<class GRAPH_T >
typedef CLoopCloserERD<GRAPH_T> mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::lc_parent_t

Handy typedefs.

type of graph constraints parent class

Definition at line 34 of file CLoopCloserERD_MR.h.

template<class GRAPH_T >
typedef CEdgeRegistrationDecider_MR<GRAPH_T> mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::mr_parent_t

parent class

Definition at line 35 of file CLoopCloserERD_MR.h.

template<class GRAPH_T >
typedef lc_parent_t::nodes_to_scans2D_t mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::nodes_to_scans2D_t

Definition at line 41 of file CLoopCloserERD_MR.h.

template<class GRAPH_T >
typedef lc_parent_t::partitions_t mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::partitions_t

Definition at line 40 of file CLoopCloserERD_MR.h.

template<class GRAPH_T >
typedef lc_parent_t::pose_t mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::pose_t

Definition at line 38 of file CLoopCloserERD_MR.h.

template<class GRAPH_T >
typedef lc_parent_t::range_ops_t mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::range_ops_t

Definition at line 39 of file CLoopCloserERD_MR.h.

Constructor & Destructor Documentation

template<class GRAPH_T >
mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::CLoopCloserERD_MR ( )

Definition at line 16 of file CLoopCloserERD_MR_impl.h.

Member Function Documentation

template<class GRAPH_T >
void mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::addBatchOfNodeIDsAndScans ( const std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &  nodeIDs_to_scans2D)
virtual
template<class GRAPH_T >
void mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::addScanMatchingEdges ( TNodeID  curr_nodeID)

Definition at line 39 of file CLoopCloserERD_MR_impl.h.

template<class GRAPH_T >
void mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::fetchNodeIDsForScanMatching ( const TNodeID &  curr_nodeID,
std::set< TNodeID > *  nodes_set 
)

Definition at line 54 of file CLoopCloserERD_MR_impl.h.

template<class GRAPH_T >
bool mrpt::graphslam::deciders::CLoopCloserERD_MR< GRAPH_T >::updateState ( mrpt::obs::CActionCollection::Ptr  action,
mrpt::obs::CSensoryFrame::Ptr  observations,
mrpt::obs::CObservation::Ptr  observation 
)

Definition at line 73 of file CLoopCloserERD_MR_impl.h.


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


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