Class LoopDetector
Defined in File loop_detector.hpp
Class Documentation
-
class LoopDetector
This class finds loops by scam matching and adds them to the pose graph.
Public Types
-
typedef pcl::PointXYZI PointT
Public Functions
Constructor of the class LoopDetector.
- Parameters:
node –
-
inline std::vector<Loop::Ptr> detect(const std::map<int, KeyFrame::Ptr> &keyframes, const std::deque<KeyFrame::Ptr> &new_keyframes, s_graphs::GraphSLAM &covisibility_graph)
Detect loops and add them to the pose graph.
- Parameters:
keyframes – Keyframes
new_keyframes – Newly registered keyframes
covisibility_graph – Pose graph
- Returns:
Loop vector
-
inline std::vector<Loop::Ptr> detect(const std::map<int, KeyFrame::Ptr> &keyframes, const std::vector<KeyFrame::Ptr> &new_keyframes, s_graphs::GraphSLAM &covisibility_graph)
-
inline std::vector<Loop::Ptr> detectWithAllKeyframes(const std::map<int, KeyFrame::Ptr> &keyframes, const std::vector<KeyFrame::Ptr> &new_keyframes, s_graphs::GraphSLAM &covisibility_graph)
-
inline bool matching(const KeyFrame::Ptr &keyframe, const KeyFrame::Ptr &prev_keyframe, Eigen::Matrix4f &relative_pose)
-
inline double get_distance_thresh() const
- Returns:
Distance treshold
-
typedef pcl::PointXYZI PointT