LoadState(FromFile) endpoints (#1203)
[RFC=0023](https://github.com/googlecartographer/rfcs/blob/master/text/0023-delete-load.md)master
parent
c249a9901d
commit
984553ee15
|
@ -21,8 +21,10 @@
|
||||||
#include "cartographer/cloud/internal/handlers/add_trajectory_handler.h"
|
#include "cartographer/cloud/internal/handlers/add_trajectory_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/finish_trajectory_handler.h"
|
#include "cartographer/cloud/internal/handlers/finish_trajectory_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/get_submap_handler.h"
|
#include "cartographer/cloud/internal/handlers/get_submap_handler.h"
|
||||||
|
#include "cartographer/cloud/internal/handlers/load_state_from_file_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/load_state_handler.h"
|
#include "cartographer/cloud/internal/handlers/load_state_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/write_state_handler.h"
|
#include "cartographer/cloud/internal/handlers/write_state_handler.h"
|
||||||
|
#include "cartographer/cloud/internal/mapping/serialization.h"
|
||||||
#include "cartographer/cloud/internal/sensor/serialization.h"
|
#include "cartographer/cloud/internal/sensor/serialization.h"
|
||||||
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
||||||
#include "cartographer/io/proto_stream_deserializer.h"
|
#include "cartographer/io/proto_stream_deserializer.h"
|
||||||
|
@ -163,13 +165,17 @@ std::map<int, int> MapBuilderStub::LoadState(
|
||||||
CHECK(reader->eof());
|
CHECK(reader->eof());
|
||||||
CHECK(client.StreamWritesDone());
|
CHECK(client.StreamWritesDone());
|
||||||
CHECK(client.StreamFinish().ok());
|
CHECK(client.StreamFinish().ok());
|
||||||
// TODO(gaschler): Return trajectory remapping.
|
return FromProto(client.response().trajectory_remapping());
|
||||||
return {};
|
|
||||||
}
|
}
|
||||||
|
|
||||||
std::map<int, int> MapBuilderStub::LoadStateFromFile(
|
std::map<int, int> MapBuilderStub::LoadStateFromFile(
|
||||||
const std::string& filename) {
|
const std::string& filename) {
|
||||||
LOG(FATAL) << "not implemented";
|
proto::LoadStateFromFileRequest request;
|
||||||
|
request.set_file_path(filename);
|
||||||
|
async_grpc::Client<handlers::LoadStateFromFileSignature> client(
|
||||||
|
client_channel_);
|
||||||
|
CHECK(client.Write(request));
|
||||||
|
return FromProto(client.response().trajectory_remapping());
|
||||||
}
|
}
|
||||||
|
|
||||||
int MapBuilderStub::num_trajectory_builders() const {
|
int MapBuilderStub::num_trajectory_builders() const {
|
||||||
|
|
|
@ -474,8 +474,13 @@ TEST_F(ClientServerTest, LoadState) {
|
||||||
kLandmarkDataProtoString,
|
kLandmarkDataProtoString,
|
||||||
});
|
});
|
||||||
|
|
||||||
stub_->LoadState(reader.get(), true);
|
auto trajectory_remapping = stub_->LoadState(reader.get(), true);
|
||||||
EXPECT_TRUE(stub_->pose_graph()->IsTrajectoryFrozen(0));
|
int expected_trajectory_id = 0;
|
||||||
|
EXPECT_EQ(trajectory_remapping.size(), 1);
|
||||||
|
EXPECT_EQ(trajectory_remapping.at(0), expected_trajectory_id);
|
||||||
|
EXPECT_TRUE(stub_->pose_graph()->IsTrajectoryFrozen(expected_trajectory_id));
|
||||||
|
EXPECT_FALSE(
|
||||||
|
stub_->pose_graph()->IsTrajectoryFinished(expected_trajectory_id));
|
||||||
server_->Shutdown();
|
server_->Shutdown();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,43 @@
|
||||||
|
/*
|
||||||
|
* Copyright 2018 The Cartographer Authors
|
||||||
|
*
|
||||||
|
* Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
* you may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "cartographer/cloud/internal/handlers/load_state_from_file_handler.h"
|
||||||
|
|
||||||
|
#include "async_grpc/rpc_handler.h"
|
||||||
|
#include "cartographer/cloud/internal/map_builder_context_interface.h"
|
||||||
|
#include "cartographer/cloud/internal/mapping/serialization.h"
|
||||||
|
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
||||||
|
#include "cartographer/common/make_unique.h"
|
||||||
|
|
||||||
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
namespace handlers {
|
||||||
|
|
||||||
|
void LoadStateFromFileHandler::OnRequest(
|
||||||
|
const proto::LoadStateFromFileRequest& request) {
|
||||||
|
// TODO(gaschler): This blocks a handler thread, consider working in
|
||||||
|
// background.
|
||||||
|
auto trajectory_remapping =
|
||||||
|
GetContext<MapBuilderContextInterface>()->map_builder().LoadStateFromFile(
|
||||||
|
request.file_path());
|
||||||
|
auto response = common::make_unique<proto::LoadStateFromFileResponse>();
|
||||||
|
*response->mutable_trajectory_remapping() = ToProto(trajectory_remapping);
|
||||||
|
Send(std::move(response));
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace handlers
|
||||||
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
|
@ -0,0 +1,42 @@
|
||||||
|
/*
|
||||||
|
* Copyright 2018 The Cartographer Authors
|
||||||
|
*
|
||||||
|
* Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
* you may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef CARTOGRAPHER_CLOUD_INTERNAL_HANDLERS_LOAD_STATE_FROM_FILE_HANDLER_H
|
||||||
|
#define CARTOGRAPHER_CLOUD_INTERNAL_HANDLERS_LOAD_STATE_FROM_FILE_HANDLER_H
|
||||||
|
|
||||||
|
#include "async_grpc/rpc_handler.h"
|
||||||
|
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
||||||
|
|
||||||
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
namespace handlers {
|
||||||
|
|
||||||
|
DEFINE_HANDLER_SIGNATURE(
|
||||||
|
LoadStateFromFileSignature, proto::LoadStateFromFileRequest,
|
||||||
|
proto::LoadStateFromFileResponse,
|
||||||
|
"/cartographer.cloud.proto.MapBuilderService/LoadStateFromFile")
|
||||||
|
|
||||||
|
class LoadStateFromFileHandler
|
||||||
|
: public async_grpc::RpcHandler<LoadStateFromFileSignature> {
|
||||||
|
public:
|
||||||
|
void OnRequest(const proto::LoadStateFromFileRequest& request) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace handlers
|
||||||
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
|
#endif // CARTOGRAPHER_CLOUD_INTERNAL_HANDLERS_LOAD_STATE_FROM_FILE_HANDLER_H
|
|
@ -18,9 +18,9 @@
|
||||||
|
|
||||||
#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/mapping/serialization.h"
|
||||||
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
||||||
#include "cartographer/common/make_unique.h"
|
#include "cartographer/common/make_unique.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
|
||||||
|
|
||||||
namespace cartographer {
|
namespace cartographer {
|
||||||
namespace cloud {
|
namespace cloud {
|
||||||
|
@ -40,9 +40,12 @@ void LoadStateHandler::OnRequest(const proto::LoadStateRequest& request) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void LoadStateHandler::OnReadsDone() {
|
void LoadStateHandler::OnReadsDone() {
|
||||||
GetContext<MapBuilderContextInterface>()->map_builder().LoadState(&reader_,
|
auto trajectory_remapping =
|
||||||
true);
|
GetContext<MapBuilderContextInterface>()->map_builder().LoadState(
|
||||||
Send(common::make_unique<google::protobuf::Empty>());
|
&reader_, true);
|
||||||
|
auto response = common::make_unique<proto::LoadStateResponse>();
|
||||||
|
*response->mutable_trajectory_remapping() = ToProto(trajectory_remapping);
|
||||||
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
|
|
|
@ -20,7 +20,6 @@
|
||||||
#include "async_grpc/rpc_handler.h"
|
#include "async_grpc/rpc_handler.h"
|
||||||
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
||||||
#include "cartographer/io/internal/in_memory_proto_stream.h"
|
#include "cartographer/io/internal/in_memory_proto_stream.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
|
||||||
|
|
||||||
namespace cartographer {
|
namespace cartographer {
|
||||||
namespace cloud {
|
namespace cloud {
|
||||||
|
@ -28,7 +27,7 @@ namespace handlers {
|
||||||
|
|
||||||
DEFINE_HANDLER_SIGNATURE(
|
DEFINE_HANDLER_SIGNATURE(
|
||||||
LoadStateSignature, async_grpc::Stream<proto::LoadStateRequest>,
|
LoadStateSignature, async_grpc::Stream<proto::LoadStateRequest>,
|
||||||
google::protobuf::Empty,
|
proto::LoadStateResponse,
|
||||||
"/cartographer.cloud.proto.MapBuilderService/LoadState")
|
"/cartographer.cloud.proto.MapBuilderService/LoadState")
|
||||||
|
|
||||||
class LoadStateHandler : public async_grpc::RpcHandler<LoadStateSignature> {
|
class LoadStateHandler : public async_grpc::RpcHandler<LoadStateSignature> {
|
||||||
|
|
|
@ -33,6 +33,7 @@
|
||||||
#include "cartographer/cloud/internal/handlers/get_trajectory_node_poses_handler.h"
|
#include "cartographer/cloud/internal/handlers/get_trajectory_node_poses_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/is_trajectory_finished_handler.h"
|
#include "cartographer/cloud/internal/handlers/is_trajectory_finished_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/is_trajectory_frozen_handler.h"
|
#include "cartographer/cloud/internal/handlers/is_trajectory_frozen_handler.h"
|
||||||
|
#include "cartographer/cloud/internal/handlers/load_state_from_file_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/load_state_handler.h"
|
#include "cartographer/cloud/internal/handlers/load_state_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.h"
|
#include "cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.h"
|
||||||
#include "cartographer/cloud/internal/handlers/receive_local_slam_results_handler.h"
|
#include "cartographer/cloud/internal/handlers/receive_local_slam_results_handler.h"
|
||||||
|
@ -88,6 +89,7 @@ MapBuilderServer::MapBuilderServer(
|
||||||
server_builder.RegisterHandler<handlers::IsTrajectoryFinishedHandler>();
|
server_builder.RegisterHandler<handlers::IsTrajectoryFinishedHandler>();
|
||||||
server_builder.RegisterHandler<handlers::IsTrajectoryFrozenHandler>();
|
server_builder.RegisterHandler<handlers::IsTrajectoryFrozenHandler>();
|
||||||
server_builder.RegisterHandler<handlers::LoadStateHandler>();
|
server_builder.RegisterHandler<handlers::LoadStateHandler>();
|
||||||
|
server_builder.RegisterHandler<handlers::LoadStateFromFileHandler>();
|
||||||
server_builder.RegisterHandler<handlers::RunFinalOptimizationHandler>();
|
server_builder.RegisterHandler<handlers::RunFinalOptimizationHandler>();
|
||||||
server_builder.RegisterHandler<handlers::WriteStateHandler>();
|
server_builder.RegisterHandler<handlers::WriteStateHandler>();
|
||||||
server_builder.RegisterHandler<handlers::SetLandmarkPoseHandler>();
|
server_builder.RegisterHandler<handlers::SetLandmarkPoseHandler>();
|
||||||
|
|
|
@ -0,0 +1,40 @@
|
||||||
|
/*
|
||||||
|
* Copyright 2018 The Cartographer Authors
|
||||||
|
*
|
||||||
|
* Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
* you may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "cartographer/cloud/internal/mapping/serialization.h"
|
||||||
|
|
||||||
|
#include "cartographer/common/port.h"
|
||||||
|
|
||||||
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
|
proto::TrajectoryRemapping ToProto(
|
||||||
|
const std::map<int, int>& trajectory_remapping) {
|
||||||
|
proto::TrajectoryRemapping proto;
|
||||||
|
*proto.mutable_serialized_trajectories_to_trajectories() =
|
||||||
|
google::protobuf::Map<int32, int32>(trajectory_remapping.begin(),
|
||||||
|
trajectory_remapping.end());
|
||||||
|
return proto;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::map<int, int> FromProto(const proto::TrajectoryRemapping& proto) {
|
||||||
|
return std::map<int, int>(
|
||||||
|
proto.serialized_trajectories_to_trajectories().begin(),
|
||||||
|
proto.serialized_trajectories_to_trajectories().end());
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
|
@ -0,0 +1,32 @@
|
||||||
|
/*
|
||||||
|
* Copyright 2018 The Cartographer Authors
|
||||||
|
*
|
||||||
|
* Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
* you may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef CARTOGRAPHER_CLOUD_INTERNAL_MAPPING_SERIALIZATION_H
|
||||||
|
#define CARTOGRAPHER_CLOUD_INTERNAL_MAPPING_SERIALIZATION_H
|
||||||
|
|
||||||
|
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
||||||
|
|
||||||
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
|
proto::TrajectoryRemapping ToProto(
|
||||||
|
const std::map<int, int>& trajectory_remapping);
|
||||||
|
std::map<int, int> FromProto(const proto::TrajectoryRemapping& proto);
|
||||||
|
|
||||||
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
|
#endif // CARTOGRAPHER_CLOUD_INTERNAL_MAPPING_SERIALIZATION_H
|
|
@ -136,6 +136,23 @@ message LoadStateRequest {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
message TrajectoryRemapping {
|
||||||
|
map<int32 /* serialized trajectory id */, int32 /* trajectory id */>
|
||||||
|
serialized_trajectories_to_trajectories = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
message LoadStateResponse {
|
||||||
|
TrajectoryRemapping trajectory_remapping = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
message LoadStateFromFileRequest {
|
||||||
|
string file_path = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
message LoadStateFromFileResponse {
|
||||||
|
TrajectoryRemapping trajectory_remapping = 1;
|
||||||
|
}
|
||||||
|
|
||||||
message GetSubmapResponse {
|
message GetSubmapResponse {
|
||||||
cartographer.mapping.proto.SubmapQuery.Response submap_query_response = 1;
|
cartographer.mapping.proto.SubmapQuery.Response submap_query_response = 1;
|
||||||
string error_msg = 2;
|
string error_msg = 2;
|
||||||
|
@ -290,7 +307,11 @@ service MapBuilderService {
|
||||||
returns (google.protobuf.Empty);
|
returns (google.protobuf.Empty);
|
||||||
|
|
||||||
// Adds serialized SLAM state data in the order defined by ProtoStreamReader.
|
// Adds serialized SLAM state data in the order defined by ProtoStreamReader.
|
||||||
rpc LoadState(stream LoadStateRequest) returns (google.protobuf.Empty);
|
rpc LoadState(stream LoadStateRequest) returns (LoadStateResponse);
|
||||||
|
|
||||||
|
// Loads a serialized SLAM state data from the host file system.
|
||||||
|
rpc LoadStateFromFile(LoadStateFromFileRequest)
|
||||||
|
returns (LoadStateFromFileResponse);
|
||||||
|
|
||||||
// Receives serialized SLAM state data in the order defined by
|
// Receives serialized SLAM state data in the order defined by
|
||||||
// ProtoStreamWriter.
|
// ProtoStreamWriter.
|
||||||
|
|
Loading…
Reference in New Issue