Swarm-SLAM  1.0.0
C-SLAM Framework
map_manager_node.cpp
Go to the documentation of this file.
2 
3 using namespace cslam;
4 
12 int main(int argc, char **argv) {
13 
14  rclcpp::init(argc, argv);
15 
16  auto node = std::make_shared<rclcpp::Node>("map_manager");
17 
18  node->declare_parameter<int>("frontend.pnp_min_inliers", 20);
19  node->declare_parameter<int>("frontend.max_queue_size", 10);
20  node->declare_parameter<int>("max_nb_robots", 1);
21  node->declare_parameter<int>("robot_id", 0);
22  node->declare_parameter<int>("frontend.map_manager_process_period_ms", 100);
23  node->declare_parameter<std::string>("frontend.sensor_type", "stereo");
24  node->declare_parameter<bool>("visualization.enable", false);
25  node->declare_parameter<int>("visualization.publishing_period_ms", 0);
26  node->declare_parameter<float>("visualization.voxel_size", 0.05);
27  node->declare_parameter<float>("visualization.max_range", 2.0);
28  node->declare_parameter<bool>("evaluation.enable_gps_recording", false);
29  node->declare_parameter<std::string>("evaluation.gps_topic", "");
30 
31  std::string sensor_type;
32  node->get_parameter("frontend.sensor_type", sensor_type);
33 
34  std::shared_ptr<IMapManager> handler;
35  if (sensor_type == "stereo") {
36  handler = std::make_shared<MapManager<StereoHandler>>(node);
37  }
38  else if (sensor_type == "rgbd") {
39  handler = std::make_shared<MapManager<RGBDHandler>>(node);
40  }
41  else {
42  RCLCPP_ERROR(node->get_logger(), "Sensor type not supported: %s",
43  sensor_type.c_str());
44  return -1;
45  }
46 
47  rclcpp::spin(node);
48 
49  rclcpp::shutdown();
50 
51  return 0;
52 }
int main(int argc, char **argv)
Node to manage the sensor data and registration.
Definition: __init__.py:1