6 template <
class DataHandlerType>
8 : node_(
node), local_data_handler_(
node) {
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_);
15 std::chrono::milliseconds period(map_manager_process_period_ms_);
17 process_timer_ = node_->create_wall_timer(
18 std::chrono::milliseconds(period),
21 RCLCPP_INFO(node_->get_logger(),
"Initialization done.");
24 template <
class DataHandlerType>
26 local_data_handler_.process_new_sensor_data();
Loop Closure Detection Management.
void process_new_sensor_data()
Looks for loop closures in the current keyframe queue.
MapManager(std::shared_ptr< rclcpp::Node > &node)
Initialization of parameters and ROS 2 objects.