Class RoomGraphGenerator

Class Documentation

class RoomGraphGenerator

Public Functions

RoomGraphGenerator(rclcpp::Node::SharedPtr node)
~RoomGraphGenerator()
Rooms get_current_room(const std::unordered_map<int, VerticalPlanes> &x_vert_planes, const std::unordered_map<int, VerticalPlanes> &y_vert_planes, const KeyFrame::Ptr keyframe, const std::unordered_map<int, Rooms> &rooms_vec)

Get the current room object.

Parameters:
  • x_vert_planes

  • y_vert_planes

  • keyframe

  • rooms_vec

Returns:

* Rooms

std::map<int, KeyFrame::Ptr> get_keyframes_inside_room(const Rooms &current_room, const std::unordered_map<int, VerticalPlanes> &x_vert_planes, const std::unordered_map<int, VerticalPlanes> &y_vert_planes, const std::map<int, KeyFrame::Ptr> &keyframes)

Get the keyframes inside room object.

Parameters:
  • current_room

  • x_vert_planes

  • y_vert_planes

  • keyframes

Returns:

* std::map<int, KeyFrame::Ptr>

std::vector<const s_graphs::VerticalPlanes*> get_room_planes(const Rooms &current_room, const std::unordered_map<int, VerticalPlanes> &x_vert_planes, const std::unordered_map<int, VerticalPlanes> &y_vert_planes)

Get the room planes object.

Parameters:
  • current_room

  • x_vert_planes

  • y_vert_planes

Returns:

* std::vector<const s_graphs::VerticalPlanes*>

void generate_local_graph(std::unique_ptr<KeyframeMapper> &keyframe_mapper, std::shared_ptr<GraphSLAM> covisibility_graph, std::map<int, s_graphs::KeyFrame::Ptr> filtered_keyframes, const Eigen::Isometry3d &odom2map, Rooms &current_room)
Parameters:
  • keyframe_mapper

  • covisibility_graph

  • filtered_keyframes

  • odom2map

  • current_room

Returns:

* void

void update_room_graph(const Rooms room, const std::shared_ptr<GraphSLAM> &covisibility_graph)

update the room graph keyframes after global optimization

Parameters:
  • room

  • covisibility_graph