From 319b60af4c5e4496b2f677c62e525e53e28ecd41 Mon Sep 17 00:00:00 2001 From: Alexander Belyaev <32522095+pifon2a@users.noreply.github.com> Date: Fri, 2 Mar 2018 23:09:24 +0100 Subject: [PATCH] Follow https://github.com/googlecartographer/cartographer/pull/955. (#751) --- .../cartographer_ros/cartographer_grpc/node_grpc_main.cc | 9 ++++----- .../cartographer_grpc/offline_node_grpc_main.cc | 2 +- 2 files changed, 5 insertions(+), 6 deletions(-) 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 210e314..42b05e8 100644 --- a/cartographer_ros/cartographer_ros/cartographer_grpc/node_grpc_main.cc +++ b/cartographer_ros/cartographer_ros/cartographer_grpc/node_grpc_main.cc @@ -42,7 +42,6 @@ DEFINE_string(load_state_filename, "", "to load, containing a saved SLAM state."); namespace cartographer_ros { -namespace cartographer_grpc { namespace { void Run() { @@ -54,8 +53,9 @@ void Run() { std::tie(node_options, trajectory_options) = LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename); - auto map_builder = cartographer::common::make_unique< - ::cartographer_grpc::mapping::MapBuilderStub>(FLAGS_server_address); + auto map_builder = + cartographer::common::make_unique<::cartographer::cloud::MapBuilderStub>( + FLAGS_server_address); Node node(node_options, std::move(map_builder), &tf_buffer); if (!FLAGS_load_state_filename.empty()) { @@ -77,7 +77,6 @@ void Run() { } } // namespace -} // namespace cartographer_grpc } // namespace cartographer_ros int main(int argc, char** argv) { @@ -93,6 +92,6 @@ int main(int argc, char** argv) { ::ros::start(); cartographer_ros::ScopedRosLogSink ros_log_sink; - cartographer_ros::cartographer_grpc::Run(); + cartographer_ros::Run(); ::ros::shutdown(); } 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 b474bc1..25c2166 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 @@ -36,7 +36,7 @@ int main(int argc, char** argv) { const cartographer_ros::MapBuilderFactory map_builder_factory = [](const ::cartographer::mapping::proto::MapBuilderOptions&) { return ::cartographer::common::make_unique< - ::cartographer_grpc::mapping::MapBuilderStub>(FLAGS_server_address); + ::cartographer::cloud::MapBuilderStub>(FLAGS_server_address); }; cartographer_ros::RunOfflineNode(map_builder_factory);