12 int main(
int argc,
char **argv) {
14 rclcpp::init(argc, argv);
16 auto node = std::make_shared<rclcpp::Node>(
"map_manager");
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",
"");
31 std::string sensor_type;
32 node->get_parameter(
"frontend.sensor_type", sensor_type);
34 std::shared_ptr<IMapManager> handler;
35 if (sensor_type ==
"stereo") {
36 handler = std::make_shared<MapManager<StereoHandler>>(
node);
38 else if (sensor_type ==
"rgbd") {
39 handler = std::make_shared<MapManager<RGBDHandler>>(
node);
42 RCLCPP_ERROR(
node->get_logger(),
"Sensor type not supported: %s",
int main(int argc, char **argv)
Node to manage the sensor data and registration.