CLoopCloserERD_MR.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+
9  */
10 
11 #pragma once
12 
14 #include <mrpt/ros1bridge/laser_scan.h>
15 #include <mrpt/graphslam/ERD/CLoopCloserERD.h>
16 #include <mrpt_msgs/NodeIDWithLaserScan.h>
17 
18 namespace mrpt
19 {
20 namespace graphslam
21 {
22 namespace deciders
23 {
31 template <class GRAPH_T>
32 class CLoopCloserERD_MR : public virtual CLoopCloserERD<GRAPH_T>,
33  public virtual CEdgeRegistrationDecider_MR<GRAPH_T>
34 {
35  public:
39  typedef CLoopCloserERD<GRAPH_T> lc_parent_t;
43  typedef typename lc_parent_t::constraint_t constraint_t;
44  typedef typename lc_parent_t::pose_t pose_t;
45  typedef typename lc_parent_t::range_ops_t range_ops_t;
46  typedef typename lc_parent_t::partitions_t partitions_t;
47  typedef typename lc_parent_t::nodes_to_scans2D_t nodes_to_scans2D_t;
49  typedef typename GRAPH_T::global_pose_t global_pose_t;
53 
54  // member implementations
55  bool updateState(
56  mrpt::obs::CActionCollection::Ptr action,
57  mrpt::obs::CSensoryFrame::Ptr observations,
58  mrpt::obs::CObservation::Ptr observation);
60  const std::map<TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr>&
61  nodeIDs_to_scans2D);
62  void addScanMatchingEdges(TNodeID curr_nodeID);
64  const TNodeID& curr_nodeID, std::set<TNodeID>* nodes_set);
65 
66  protected:
67 };
68 
69 } // namespace deciders
70 } // namespace graphslam
71 } // namespace mrpt
72 
73 #include "CLoopCloserERD_MR_impl.h"
lc_parent_t::nodes_to_scans2D_t nodes_to_scans2D_t
bool updateState(mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation)
CEdgeRegistrationDecider_MR< GRAPH_T > mr_parent_t
void addBatchOfNodeIDsAndScans(const std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodeIDs_to_scans2D)
void fetchNodeIDsForScanMatching(const TNodeID &curr_nodeID, std::set< TNodeID > *nodes_set)
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T > engine_t
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM ...
CLoopCloserERD< GRAPH_T > lc_parent_t
Handy typedefs.


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