14 #include <mrpt/ros1bridge/laser_scan.h> 15 #include <mrpt/graphslam/ERD/CLoopCloserERD.h> 16 #include <mrpt_msgs/NodeIDWithLaserScan.h> 31 template <
class GRAPH_T>
44 typedef typename lc_parent_t::pose_t
pose_t;
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>&
64 const TNodeID& curr_nodeID, std::set<TNodeID>* nodes_set);
Edge Registration Decider virtual method.
void addScanMatchingEdges(TNodeID curr_nodeID)
CLoopCloserERD_MR< GRAPH_T > decider_t
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)
lc_parent_t::pose_t pose_t
CEdgeRegistrationDecider_MR< GRAPH_T > mr_parent_t
lc_parent_t::constraint_t constraint_t
void addBatchOfNodeIDsAndScans(const std::map< TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodeIDs_to_scans2D)
GRAPH_T::global_pose_t global_pose_t
lc_parent_t::range_ops_t range_ops_t
void fetchNodeIDsForScanMatching(const TNodeID &curr_nodeID, std::set< TNodeID > *nodes_set)
mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T > engine_t
lc_parent_t::partitions_t partitions_t
mrpt::graphslam::CGraphSlamEngine derived class for executing multi-robot graphSLAM ...
CLoopCloserERD< GRAPH_T > lc_parent_t
Handy typedefs.