Class LoopDetectorNode¶
Defined in File loop-detector-node.h
Inheritance Relationships¶
Base Type¶
public common::FileSerializable< proto::LoopDetectorNode >
(Template Class FileSerializable)
Class Documentation¶
-
class loop_detector_node::LoopDetectorNode : public common::FileSerializable<proto::LoopDetectorNode>¶
Public Types
-
typedef vi_map::MissionBaseFrameMap MissionBaseFrameMap¶
-
typedef vi_map::MissionMap MissionMap¶
-
typedef vi_map::MissionId MissionId¶
-
typedef std::unordered_map<vi_map::LandmarkId, vi_map::LandmarkId> LandmarkToLandmarkMap¶
Public Functions
-
LoopDetectorNode()¶
-
bool hasMissionInDatabase(const vi_map::MissionId &mission_id) const¶
-
void addLandmarkSetToDatabase(const vi_map::LandmarkIdSet &landmark_id_set, const vi_map::VIMap &map)¶
-
void addLocalizationSummaryMapToDatabase(const summary_map::LocalizationSummaryMap &localization_summary_map)¶
-
bool findVertexInDatabase(const vi_map::Vertex &query_vertex, const bool merge_landmarks, const bool add_lc_edges, vi_map::VIMap *map, pose::Transformation *T_G_I, unsigned int *num_of_lc_matches, vi_map::LoopClosureConstraint *inlier_constraint) const¶
-
bool findNFrameInDatabase(const aslam::VisualNFrame &n_frame, const bool skip_untracked_keypoints, vi_map::VIMap *map, pose::Transformation *T_G_I, unsigned int *num_of_lc_matches, vi_map::VertexKeyPointToStructureMatchList *inlier_structure_matches, pose_graph::VertexId *vertex_id_closest_to_structure_matches) const¶
-
bool findNFrameInSummaryMapDatabase(const aslam::VisualNFrame &n_frame, const bool skip_untracked_keypoints, const summary_map::LocalizationSummaryMap &localization_summary_map, pose::Transformation *T_G_I, unsigned int *num_of_lc_matches, vi_map::VertexKeyPointToStructureMatchList *inlier_structure_matches) const¶
-
void detectLoopClosuresMissionToDatabase(const MissionId &mission_id, const bool merge_landmarks, const bool add_lc_edges, int *num_vertex_candidate_links, double *summary_landmark_match_inlier_ratio, vi_map::VIMap *map, pose::Transformation *T_G_M_estimate, vi_map::LoopClosureConstraintVector *inlier_constraints) const¶
-
void detectLoopClosuresVerticesToDatabase(const pose_graph::VertexIdList &vertices, const bool merge_landmarks, const bool add_lc_edges, int *num_vertex_candidate_links, double *summary_landmark_match_inlier_ratio, vi_map::VIMap *map, pose::Transformation *T_G_M_estimate, vi_map::LoopClosureConstraintVector *inlier_constraints) const¶
-
void instantiateVisualizer()¶
-
void clear()¶
-
std::string printStatus() const¶
-
virtual void serialize(proto::LoopDetectorNode *proto_loop_detector_node) const override¶
-
virtual void deserialize(const proto::LoopDetectorNode &proto_loop_detector_node) override¶
Public Members
- LoopDetectorNode
Public Static Functions
-
static const std::string &getDefaultSerializationFilename()¶
-
typedef vi_map::MissionBaseFrameMap MissionBaseFrameMap¶