Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/cloud/client/map_builder_stub.h"
00018 #include "cartographer_ros/offline_node.h"
00019 #include "cartographer_ros/ros_log_sink.h"
00020 #include "gflags/gflags.h"
00021 #include "ros/ros.h"
00022
00023 DEFINE_string(server_address, "localhost:50051",
00024 "gRPC server address to "
00025 "stream the sensor data to.");
00026 DEFINE_string(client_id, "",
00027 "Cartographer client ID to use when connecting to the server.");
00028
00029 int main(int argc, char** argv) {
00030 google::InitGoogleLogging(argv[0]);
00031 google::ParseCommandLineFlags(&argc, &argv, true);
00032
00033 CHECK(!FLAGS_client_id.empty()) << "-client_id is missing.";
00034
00035 ::ros::init(argc, argv, "cartographer_grpc_offline_node");
00036 ::ros::start();
00037
00038 cartographer_ros::ScopedRosLogSink ros_log_sink;
00039
00040 const cartographer_ros::MapBuilderFactory map_builder_factory =
00041 [](const ::cartographer::mapping::proto::MapBuilderOptions&) {
00042 return absl::make_unique< ::cartographer::cloud::MapBuilderStub>(
00043 FLAGS_server_address, FLAGS_client_id);
00044 };
00045
00046 cartographer_ros::RunOfflineNode(map_builder_factory);
00047
00048 ::ros::shutdown();
00049 }