Add WriteStateToFileResponse. (#1428)

Changes the public map builder API, but is required to not break the ROS API.
See also https://github.com/googlecartographer/cartographer_ros/pull/1014 and #1422
master
Michael Grupp 2018-09-15 00:03:30 +02:00 committed by Wally B. Feed
parent d53ac8102b
commit ba859a6ed5
9 changed files with 30 additions and 14 deletions

View File

@ -153,7 +153,7 @@ void MapBuilderStub::SerializeState(bool include_unfinished_submaps,
} }
} }
void MapBuilderStub::SerializeStateToFile(bool include_unfinished_submaps, bool MapBuilderStub::SerializeStateToFile(bool include_unfinished_submaps,
const std::string& filename) { const std::string& filename) {
if (include_unfinished_submaps) { if (include_unfinished_submaps) {
LOG(WARNING) << "Serializing unfinished submaps is currently unsupported. " LOG(WARNING) << "Serializing unfinished submaps is currently unsupported. "
@ -164,9 +164,12 @@ void MapBuilderStub::SerializeStateToFile(bool include_unfinished_submaps,
::grpc::Status status; ::grpc::Status status;
async_grpc::Client<handlers::WriteStateToFileSignature> client( async_grpc::Client<handlers::WriteStateToFileSignature> client(
client_channel_); client_channel_);
CHECK(client.Write(request, &status)) if (!client.Write(request, &status)) {
LOG(ERROR) << "WriteStateToFileRequest failed - "
<< "code: " << status.error_code() << "code: " << status.error_code()
<< " reason: " << status.error_message(); << " reason: " << status.error_message();
}
return client.response().success();
} }
std::map<int, int> MapBuilderStub::LoadState( std::map<int, int> MapBuilderStub::LoadState(

View File

@ -50,7 +50,7 @@ class MapBuilderStub : public mapping::MapBuilderInterface {
mapping::proto::SubmapQuery::Response* response) override; mapping::proto::SubmapQuery::Response* response) override;
void SerializeState(bool include_unfinished_submaps, void SerializeState(bool include_unfinished_submaps,
io::ProtoStreamWriterInterface* writer) override; io::ProtoStreamWriterInterface* writer) override;
void SerializeStateToFile(bool include_unfinished_submaps, bool SerializeStateToFile(bool include_unfinished_submaps,
const std::string& filename) override; const std::string& filename) override;
std::map<int, int> LoadState(io::ProtoStreamReaderInterface* reader, std::map<int, int> LoadState(io::ProtoStreamReaderInterface* reader,
bool load_frozen_state) override; bool load_frozen_state) override;

View File

@ -16,6 +16,7 @@
#include "cartographer/cloud/internal/handlers/write_state_to_file_handler.h" #include "cartographer/cloud/internal/handlers/write_state_to_file_handler.h"
#include "absl/memory/memory.h"
#include "async_grpc/rpc_handler.h" #include "async_grpc/rpc_handler.h"
#include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/map_builder_context_interface.h"
#include "cartographer/cloud/internal/map_builder_server.h" #include "cartographer/cloud/internal/map_builder_server.h"
@ -32,8 +33,14 @@ void WriteStateToFileHandler::OnRequest(
Finish(::grpc::Status(::grpc::INVALID_ARGUMENT, "Filename empty.")); Finish(::grpc::Status(::grpc::INVALID_ARGUMENT, "Filename empty."));
return; return;
} }
GetContext<MapBuilderContextInterface>()->map_builder().SerializeStateToFile( bool success =
GetContext<MapBuilderContextInterface>()
->map_builder()
.SerializeStateToFile(
/*include_unfinished_submaps=*/false, request.filename()); /*include_unfinished_submaps=*/false, request.filename());
auto response = absl::make_unique<proto::WriteStateToFileResponse>();
response->set_success(success);
Send(std::move(response));
} }
} // namespace handlers } // namespace handlers

View File

@ -27,7 +27,7 @@ namespace handlers {
DEFINE_HANDLER_SIGNATURE( DEFINE_HANDLER_SIGNATURE(
WriteStateToFileSignature, proto::WriteStateToFileRequest, WriteStateToFileSignature, proto::WriteStateToFileRequest,
google::protobuf::Empty, proto::WriteStateToFileResponse,
"/cartographer.cloud.proto.MapBuilderService/WriteStateToFile") "/cartographer.cloud.proto.MapBuilderService/WriteStateToFile")
class WriteStateToFileHandler class WriteStateToFileHandler

View File

@ -232,6 +232,10 @@ message WriteStateToFileRequest {
string filename = 1; string filename = 1;
} }
message WriteStateToFileResponse {
bool success = 1;
}
message IsTrajectoryFinishedRequest { message IsTrajectoryFinishedRequest {
int32 trajectory_id = 1; int32 trajectory_id = 1;
} }
@ -345,5 +349,6 @@ service MapBuilderService {
rpc WriteState(google.protobuf.Empty) returns (stream WriteStateResponse); rpc WriteState(google.protobuf.Empty) returns (stream WriteStateResponse);
// Writes the serialized SLAM state to the host file system. // Writes the serialized SLAM state to the host file system.
rpc WriteStateToFile(WriteStateToFileRequest) returns (google.protobuf.Empty); rpc WriteStateToFile(WriteStateToFileRequest)
returns (WriteStateToFileResponse);
} }

View File

@ -48,7 +48,7 @@ class MockMapBuilder : public mapping::MapBuilderInterface {
std::string(const mapping::SubmapId &, std::string(const mapping::SubmapId &,
mapping::proto::SubmapQuery::Response *)); mapping::proto::SubmapQuery::Response *));
MOCK_METHOD2(SerializeState, void(bool, io::ProtoStreamWriterInterface *)); MOCK_METHOD2(SerializeState, void(bool, io::ProtoStreamWriterInterface *));
MOCK_METHOD2(SerializeStateToFile, void(bool, const std::string &)); MOCK_METHOD2(SerializeStateToFile, bool(bool, const std::string &));
MOCK_METHOD2(LoadState, MOCK_METHOD2(LoadState,
std::map<int, int>(io::ProtoStreamReaderInterface *, bool)); std::map<int, int>(io::ProtoStreamReaderInterface *, bool));
MOCK_METHOD2(LoadStateFromFile, MOCK_METHOD2(LoadStateFromFile,

View File

@ -212,12 +212,12 @@ void MapBuilder::SerializeState(bool include_unfinished_submaps,
include_unfinished_submaps); include_unfinished_submaps);
} }
void MapBuilder::SerializeStateToFile(bool include_unfinished_submaps, bool MapBuilder::SerializeStateToFile(bool include_unfinished_submaps,
const std::string& filename) { const std::string& filename) {
io::ProtoStreamWriter writer(filename); io::ProtoStreamWriter writer(filename);
io::WritePbStream(*pose_graph_, all_trajectory_builder_options_, &writer, io::WritePbStream(*pose_graph_, all_trajectory_builder_options_, &writer,
include_unfinished_submaps); include_unfinished_submaps);
writer.Close(); return (writer.Close());
} }
std::map<int, int> MapBuilder::LoadState( std::map<int, int> MapBuilder::LoadState(

View File

@ -59,7 +59,7 @@ class MapBuilder : public MapBuilderInterface {
void SerializeState(bool include_unfinished_submaps, void SerializeState(bool include_unfinished_submaps,
io::ProtoStreamWriterInterface *writer) override; io::ProtoStreamWriterInterface *writer) override;
void SerializeStateToFile(bool include_unfinished_submaps, bool SerializeStateToFile(bool include_unfinished_submaps,
const std::string &filename) override; const std::string &filename) override;
std::map<int, int> LoadState(io::ProtoStreamReaderInterface *reader, std::map<int, int> LoadState(io::ProtoStreamReaderInterface *reader,

View File

@ -88,7 +88,8 @@ class MapBuilderInterface {
// 'include_unfinished_submaps' is set to true, unfinished submaps, i.e. // 'include_unfinished_submaps' is set to true, unfinished submaps, i.e.
// submaps that have not yet received all rangefinder data insertions, will // submaps that have not yet received all rangefinder data insertions, will
// be included in the serialized state. // be included in the serialized state.
virtual void SerializeStateToFile(bool include_unfinished_submaps, // Returns true if the file was successfully written.
virtual bool SerializeStateToFile(bool include_unfinished_submaps,
const std::string& filename) = 0; const std::string& filename) = 0;
// Loads the SLAM state from a proto stream. Returns the remapping of new // Loads the SLAM state from a proto stream. Returns the remapping of new