Follow googlecartographer/cartographer#1241 (#923)
parent
168f4cc53f
commit
e07c2261b6
|
@ -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();
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -31,6 +31,7 @@
|
|||
|
||||
<node name="cartographer_grpc_node" pkg="cartographer_ros"
|
||||
type="cartographer_grpc_node" args="
|
||||
-client_id CLIENT_ID
|
||||
-configuration_directory $(find cartographer_ros)/configuration_files
|
||||
-configuration_basename backpack_2d.lua"
|
||||
output="screen">
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
|
||||
<node name="cartographer_grpc_node" pkg="cartographer_ros"
|
||||
type="cartographer_grpc_node" args="
|
||||
-client_id CLIENT_ID
|
||||
-configuration_directory $(find cartographer_ros)/configuration_files
|
||||
-configuration_basename backpack_2d.lua
|
||||
-map_filename $(arg map_filename)"
|
||||
|
|
Loading…
Reference in New Issue