diff --git a/cartographer_ros/cartographer_ros/cartographer_grpc/node_grpc_main.cc b/cartographer_ros/cartographer_ros/cartographer_grpc/node_grpc_main.cc index 1ddb0ef..0709221 100644 --- a/cartographer_ros/cartographer_ros/cartographer_grpc/node_grpc_main.cc +++ b/cartographer_ros/cartographer_ros/cartographer_grpc/node_grpc_main.cc @@ -44,6 +44,8 @@ DEFINE_string( DEFINE_string(load_state_filename, "", "If non-empty, filename of a .pbstream file " "to load, containing a saved SLAM state."); +DEFINE_string(client_id, "", + "Cartographer client ID to use when connecting to the server."); namespace cartographer_ros { namespace { @@ -59,7 +61,7 @@ void Run() { auto map_builder = cartographer::common::make_unique<::cartographer::cloud::MapBuilderStub>( - FLAGS_server_address); + FLAGS_server_address, FLAGS_client_id); Node node(node_options, std::move(map_builder), &tf_buffer, FLAGS_collect_metrics); @@ -92,6 +94,7 @@ int main(int argc, char** argv) { << "-configuration_directory is missing."; CHECK(!FLAGS_configuration_basename.empty()) << "-configuration_basename is missing."; + CHECK(!FLAGS_client_id.empty()) << "-client_id is missing."; ::ros::init(argc, argv, "cartographer_grpc_node"); ::ros::start(); diff --git a/cartographer_ros/cartographer_ros/cartographer_grpc/offline_node_grpc_main.cc b/cartographer_ros/cartographer_ros/cartographer_grpc/offline_node_grpc_main.cc index ffaabf1..621826b 100644 --- a/cartographer_ros/cartographer_ros/cartographer_grpc/offline_node_grpc_main.cc +++ b/cartographer_ros/cartographer_ros/cartographer_grpc/offline_node_grpc_main.cc @@ -23,11 +23,15 @@ DEFINE_string(server_address, "localhost:50051", "gRPC server address to " "stream the sensor data to."); +DEFINE_string(client_id, "", + "Cartographer client ID to use when connecting to the server."); int main(int argc, char** argv) { google::InitGoogleLogging(argv[0]); google::ParseCommandLineFlags(&argc, &argv, true); + CHECK(!FLAGS_client_id.empty()) << "-client_id is missing."; + ::ros::init(argc, argv, "cartographer_grpc_offline_node"); ::ros::start(); @@ -36,7 +40,8 @@ int main(int argc, char** argv) { const cartographer_ros::MapBuilderFactory map_builder_factory = [](const ::cartographer::mapping::proto::MapBuilderOptions&) { return ::cartographer::common::make_unique< - ::cartographer::cloud::MapBuilderStub>(FLAGS_server_address); + ::cartographer::cloud::MapBuilderStub>(FLAGS_server_address, + FLAGS_client_id); }; cartographer_ros::RunOfflineNode(map_builder_factory); diff --git a/cartographer_ros/launch/grpc_demo_backpack_2d.launch b/cartographer_ros/launch/grpc_demo_backpack_2d.launch index b8bf583..9f942a7 100644 --- a/cartographer_ros/launch/grpc_demo_backpack_2d.launch +++ b/cartographer_ros/launch/grpc_demo_backpack_2d.launch @@ -31,6 +31,7 @@ diff --git a/cartographer_ros/launch/grpc_demo_backpack_2d_localization.launch b/cartographer_ros/launch/grpc_demo_backpack_2d_localization.launch index 72be95a..64bf878 100644 --- a/cartographer_ros/launch/grpc_demo_backpack_2d_localization.launch +++ b/cartographer_ros/launch/grpc_demo_backpack_2d_localization.launch @@ -25,6 +25,7 @@