CLoopCloserERD_MR.h
Go to the documentation of this file.
00001 /* +---------------------------------------------------------------------------+
00002    |                     Mobile Robot Programming Toolkit (MRPT)               |
00003    |                          http://www.mrpt.org/                             |
00004    |                                                                           |
00005    | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file        |
00006    | See: http://www.mrpt.org/Authors - All rights reserved.                   |
00007    | Released under BSD License. See details in http://www.mrpt.org/License    |
00008    +---------------------------------------------------------------------------+ */
00009 
00010 #pragma once
00011 
00012 #include "mrpt_graphslam_2d/interfaces/CEdgeRegistrationDecider_MR.h"
00013 #include <mrpt_bridge/laser_scan.h>
00014 #include <mrpt/graphslam/ERD/CLoopCloserERD.h>
00015 #include <mrpt_msgs/NodeIDWithLaserScan.h>
00016 
00017 namespace mrpt { namespace graphslam { namespace deciders {
00018 
00025 template<class GRAPH_T>
00026 class CLoopCloserERD_MR :
00027         public virtual CLoopCloserERD<GRAPH_T>,
00028         public virtual CEdgeRegistrationDecider_MR<GRAPH_T>
00029 {
00030 public:
00034         typedef CLoopCloserERD<GRAPH_T> lc_parent_t; 
00035         typedef CEdgeRegistrationDecider_MR<GRAPH_T> mr_parent_t; 
00036         typedef CLoopCloserERD_MR<GRAPH_T> decider_t; 
00037         typedef typename lc_parent_t::constraint_t constraint_t;
00038         typedef typename lc_parent_t::pose_t pose_t;
00039         typedef typename lc_parent_t::range_ops_t range_ops_t;
00040         typedef typename lc_parent_t::partitions_t partitions_t;
00041         typedef typename lc_parent_t::nodes_to_scans2D_t nodes_to_scans2D_t;
00042         typedef mrpt::graphslam::CGraphSlamEngine_MR<GRAPH_T> engine_t;
00043         typedef typename GRAPH_T::global_pose_t global_pose_t;
00046         CLoopCloserERD_MR();
00047 
00048         // member implementations
00049         bool updateState(
00050                         mrpt::obs::CActionCollection::Ptr action,
00051                         mrpt::obs::CSensoryFrame::Ptr observations,
00052                         mrpt::obs::CObservation::Ptr observation );
00053         void addBatchOfNodeIDsAndScans(
00054                         const std::map<
00055                                 TNodeID,
00056                                 mrpt::obs::CObservation2DRangeScan::Ptr>& nodeIDs_to_scans2D);
00057         void addScanMatchingEdges(TNodeID curr_nodeID);
00058         void fetchNodeIDsForScanMatching(
00059                         const TNodeID& curr_nodeID,
00060                         std::set<TNodeID>* nodes_set);
00061 
00062 protected:
00063 
00064 };
00065 
00066 } } } // end of namespaces
00067 
00068 #include "CLoopCloserERD_MR_impl.h"


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Jun 6 2019 21:40:26