Swarm-SLAM  1.0.0
C-SLAM Framework
map_manager.cpp
Go to the documentation of this file.
3 
4 using namespace cslam;
5 
6 template <class DataHandlerType>
7 MapManager<DataHandlerType>::MapManager(std::shared_ptr<rclcpp::Node> &node)
8  : node_(node), local_data_handler_(node) {
9 
10  node_->get_parameter("max_nb_robots", max_nb_robots_);
11  node_->get_parameter("robot_id", robot_id_);
12  node_->get_parameter("frontend.map_manager_process_period_ms",
13  map_manager_process_period_ms_);
14 
15  std::chrono::milliseconds period(map_manager_process_period_ms_);
16 
17  process_timer_ = node_->create_wall_timer(
18  std::chrono::milliseconds(period),
20 
21  RCLCPP_INFO(node_->get_logger(), "Initialization done.");
22 }
23 
24 template <class DataHandlerType>
26  local_data_handler_.process_new_sensor_data();
27 }
Loop Closure Detection Management.
Definition: map_manager.h:32
void process_new_sensor_data()
Looks for loop closures in the current keyframe queue.
Definition: map_manager.cpp:25
MapManager(std::shared_ptr< rclcpp::Node > &node)
Initialization of parameters and ROS 2 objects.
Definition: map_manager.cpp:7
Definition: __init__.py:1