Class KeyframeMapper

Class Documentation

class KeyframeMapper

Public Functions

KeyframeMapper(const rclcpp::Node::SharedPtr node)

Constructor for class KeyframeMapper.

Parameters:

private_nh

~KeyframeMapper()
int map_keyframes(std::shared_ptr<GraphSLAM> &covisibility_graph, Eigen::Isometry3d odom2map, std::deque<KeyFrame::Ptr> &keyframe_queue, std::map<int, KeyFrame::Ptr> &keyframes, std::deque<KeyFrame::Ptr> &new_keyframes, g2o::VertexSE3 *&anchor_node, g2o::EdgeSE3 *&anchor_edge, std::unordered_map<rclcpp::Time, KeyFrame::Ptr, RosTimeHash> &keyframe_hash)
Parameters:
  • covisibility_graph

  • odom2map

  • keyframe_queue

  • keyframes

  • new_keyframes

  • anchor_node

  • anchor_edge

  • keyframe_hash

Returns:

void map_keyframes(std::shared_ptr<GraphSLAM> &local_graph, std::shared_ptr<GraphSLAM> &covisibility_graph, const Eigen::Isometry3d &odom2map, std::deque<KeyFrame::Ptr> &keyframe_queue, std::map<int, s_graphs::KeyFrame::Ptr> &keyframes, g2o::VertexSE3 *&anchor_node, g2o::EdgeSE3 *&anchor_edge)
Parameters:
  • local_graph

  • covisibility_graph

  • odom2map

  • keyframe_queue

  • keyframes

  • anchor_node

  • anchor_edge

Returns:

* void

void add_anchor_node(std::shared_ptr<GraphSLAM> &local_graph, KeyFrame::Ptr keyframe, g2o::VertexSE3 *&anchor_node, g2o::EdgeSE3 *&anchor_edge, bool use_vertex_id = false)
Parameters:
  • local_graph

  • keyframe

  • anchor_node

  • anchor_edge

  • use_vertex_size_id

Returns:

* void

void remap_delayed_keyframe(std::shared_ptr<GraphSLAM> &covisibility_graph, KeyFrame::Ptr keyframe, KeyFrame::Ptr prev_keyframe)
Parameters:
  • covisibility_graph

  • keyframe

  • prev_keyframe

Returns:

* void