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

Node Registration Decider Interface Class. More...

#include <CNodeRegistrationDecider_MR.h>

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

Public Types

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 Types inherited from mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T >
typedef GRAPH_T::constraint_t constraint_t
 
typedef GRAPH_T::constraint_t constraint_t
 
typedef GRAPH_T::global_pose_t global_pose_t
 
typedef GRAPH_T::global_pose_t global_pose_t
 
typedef mrpt::math::CMatrixFixedNumeric< double, constraint_t::state_length, constraint_t::state_length > inf_mat_t
 
typedef mrpt::math::CMatrixFixedNumeric< double, constraint_t::state_length, constraint_t::state_length > inf_mat_t
 
typedef mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T > parent_t
 
typedef mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T > parent_t
 
typedef GRAPH_T::constraint_t::type_value pose_t
 
typedef GRAPH_T::constraint_t::type_value pose_t
 

Public Member Functions

 CNodeRegistrationDecider_MR ()
 
 ~CNodeRegistrationDecider_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 ()
 
- Public Member Functions inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >
 CRegistrationDeciderOrOptimizer ()
 
std::string getClassName () const
 
virtual void initializeLoggers (const std::string &name)
 
virtual void initializeVisuals ()
 
bool isMultiRobotSlamClass ()
 
virtual void loadParams (const std::string &source_fname)
 
virtual void notifyOfWindowEvents (const std::map< std::string, bool > &events_occurred)
 
virtual void printParams () const
 
virtual void setClassName (const std::string &name)
 
virtual void setCriticalSectionPtr (mrpt::synch::CCriticalSection *graph_section)
 
virtual void setGraphPtr (GRAPH_T *graph)
 
virtual void setWindowManagerPtr (mrpt::graphslam::CWindowManager *win_manager)
 
virtual void updateVisuals ()
 
virtual ~CRegistrationDeciderOrOptimizer ()
 
- Public Member Functions inherited from mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T >
 CNodeRegistrationDecider ()
 
virtual global_pose_t getCurrentRobotPosEstimation () const
 
virtual void getDescriptiveReport (std::string *report_str) const
 
virtual bool updateState (mrpt::obs::CActionCollectionPtr action, mrpt::obs::CSensoryFramePtr observations, mrpt::obs::CObservationPtr observation)=0
 
virtual ~CNodeRegistrationDecider ()
 

Protected Member Functions

template<>
void addNodeAnnotsToPose (global_pose_t *pose) const
 
void addNodeAnnotsToPose (global_pose_t *pose) const
 Decorate a pose according to the TMRSlamNodeAnnotation fields. More...
 
- Protected Member Functions inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >
virtual void assertVisualsVars ()
 
- Protected Member Functions inherited from mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T >
virtual bool checkRegistrationCondition ()
 
bool registerNewNodeAtEnd (const typename GRAPH_T::constraint_t &constraint)
 
bool registerNewNodeAtEnd ()
 
bool registerNewNodeAtEnd ()
 
bool registerNewNodeAtEnd (const typename GRAPH_T::constraint_t &constraint)
 
void resetPDF (constraint_t *c)
 

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...
 
- Protected Attributes inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >
bool is_mr_slam_class
 
std::string m_class_name
 
GRAPH_T * m_graph
 
mrpt::synch::CCriticalSectionm_graph_section
 
bool m_initialized_visuals
 
mrpt::utils::CTimeLogger m_time_logger
 
mrpt::gui::CDisplayWindow3Dm_win
 
mrpt::graphslam::CWindowManagerm_win_manager
 
mrpt::graphslam::CWindowObserverm_win_observer
 
- Protected Attributes inherited from mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T >
inf_mat_t m_init_inf_mat
 
mrpt::utils::TNodeID m_prev_registered_nodeID
 
constraint_t m_since_prev_node_PDF
 
- Static Protected Attributes inherited from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >
static const std::string header_sep
 
static const std::string report_sep
 

Detailed Description

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

Node Registration Decider Interface Class.

Node Registration Decider classes that are to be used in a multi-robot SLAM scheme according to the Condensed Measurements multi-robot strategy by M.T. Lazaro et al. [1] are to inherit from this method.

Note
Condensed Measurements-related classes are suffixed with _MR.
For an example of inheriting from this class, see the mrpt::graphslam::deciders::CFixedIntervalsNRD_MR.

[1] Multi-robot SLAM using Condensed Measurements - M.T. Lazaro, L.M. Paz, P. Pinies, J.A. Castellanos, G. Grisetti

Definition at line 35 of file CNodeRegistrationDecider_MR.h.

Member Typedef Documentation

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

Definition at line 40 of file CNodeRegistrationDecider_MR.h.

Constructor & Destructor Documentation

Definition at line 15 of file CNodeRegistrationDecider_MR_impl.h.

Definition at line 18 of file CNodeRegistrationDecider_MR_impl.h.

Member Function Documentation

template<>
void mrpt::graphslam::deciders::CNodeRegistrationDecider_MR< mrpt::graphs::CNetworkOfPoses2DInf_NA >::addNodeAnnotsToPose ( global_pose_t pose) const
protectedvirtual
template<class GRAPH_T >
void mrpt::graphslam::deciders::CNodeRegistrationDecider_MR< GRAPH_T >::addNodeAnnotsToPose ( global_pose_t pose) const
protectedvirtual

Decorate a pose according to the TMRSlamNodeAnnotation fields.

Note
Do this only for the nodes that are initially registered in the graph by the current CGraphSlamEngine_t class. Nodes of other graphSLAM-agents that are to be integrated must have already filled these fields.

Reimplemented from mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T >.

Definition at line 21 of file CNodeRegistrationDecider_MR_impl.h.


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


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sat May 2 2020 03:44:18