Endpoints for DeleteTrajectory (#1207)
[RFC=0023](https://github.com/googlecartographer/rfcs/blob/master/text/0023-delete-load.md)master
parent
d36cbc39b8
commit
c249a9901d
|
@ -16,6 +16,7 @@
|
|||
|
||||
#include "cartographer/cloud/internal/client/pose_graph_stub.h"
|
||||
#include "async_grpc/client.h"
|
||||
#include "cartographer/cloud/internal/handlers/delete_trajectory_handler.h"
|
||||
#include "cartographer/cloud/internal/handlers/get_all_submap_poses.h"
|
||||
#include "cartographer/cloud/internal/handlers/get_constraints_handler.h"
|
||||
#include "cartographer/cloud/internal/handlers/get_landmark_poses_handler.h"
|
||||
|
@ -136,7 +137,11 @@ void PoseGraphStub::SetLandmarkPose(const std::string& landmark_id,
|
|||
}
|
||||
|
||||
void PoseGraphStub::DeleteTrajectory(int trajectory_id) {
|
||||
LOG(FATAL) << "not implemented";
|
||||
proto::DeleteTrajectoryRequest request;
|
||||
request.set_trajectory_id(trajectory_id);
|
||||
async_grpc::Client<handlers::DeleteTrajectorySignature> client(
|
||||
client_channel_);
|
||||
CHECK(client.Write(request));
|
||||
}
|
||||
|
||||
bool PoseGraphStub::IsTrajectoryFinished(int trajectory_id) const {
|
||||
|
|
|
@ -318,6 +318,37 @@ TEST_F(ClientServerTest, LocalSlam2D) {
|
|||
server_->Shutdown();
|
||||
}
|
||||
|
||||
TEST_F(ClientServerTest, LocalSlamAndDelete2D) {
|
||||
InitializeRealServer();
|
||||
server_->Start();
|
||||
InitializeStub();
|
||||
int trajectory_id =
|
||||
stub_->AddTrajectoryBuilder({kRangeSensorId}, trajectory_builder_options_,
|
||||
local_slam_result_callback_);
|
||||
TrajectoryBuilderInterface* trajectory_stub =
|
||||
stub_->GetTrajectoryBuilder(trajectory_id);
|
||||
const auto measurements = mapping::testing::GenerateFakeRangeMeasurements(
|
||||
kTravelDistance, kDuration, kTimeStep);
|
||||
for (const auto& measurement : measurements) {
|
||||
trajectory_stub->AddSensorData(kRangeSensorId.id, measurement);
|
||||
}
|
||||
WaitForLocalSlamResults(measurements.size());
|
||||
stub_->pose_graph()->RunFinalOptimization();
|
||||
// TODO(gaschler): Enable after pending PR has merged.
|
||||
// EXPECT_EQ(stub_->pose_graph()->GetTrajectoryStates().at(trajectory_id),
|
||||
// PoseGraphInterface::TrajectoryState::ACTIVE);
|
||||
EXPECT_GT(stub_->pose_graph()->GetAllSubmapPoses().size(), 0);
|
||||
EXPECT_GT(stub_->pose_graph()->GetTrajectoryNodePoses().size(), 0);
|
||||
stub_->FinishTrajectory(trajectory_id);
|
||||
stub_->pose_graph()->DeleteTrajectory(trajectory_id);
|
||||
stub_->pose_graph()->RunFinalOptimization();
|
||||
// EXPECT_EQ(stub_->pose_graph()->GetTrajectoryStates().at(trajectory_id),
|
||||
// PoseGraphInterface::TrajectoryState::DELETED);
|
||||
EXPECT_EQ(stub_->pose_graph()->GetAllSubmapPoses().size(), 0);
|
||||
EXPECT_EQ(stub_->pose_graph()->GetTrajectoryNodePoses().size(), 0);
|
||||
server_->Shutdown();
|
||||
}
|
||||
|
||||
TEST_F(ClientServerTest, GlobalSlam3D) {
|
||||
map_builder_server_options_.mutable_map_builder_options()
|
||||
->set_use_trajectory_builder_2d(false);
|
||||
|
|
|
@ -0,0 +1,41 @@
|
|||
/*
|
||||
* 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/delete_trajectory_handler.h"
|
||||
|
||||
#include "async_grpc/rpc_handler.h"
|
||||
#include "cartographer/cloud/internal/map_builder_context_interface.h"
|
||||
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "google/protobuf/empty.pb.h"
|
||||
|
||||
namespace cartographer {
|
||||
namespace cloud {
|
||||
namespace handlers {
|
||||
|
||||
void DeleteTrajectoryHandler::OnRequest(
|
||||
const proto::DeleteTrajectoryRequest& request) {
|
||||
GetContext<MapBuilderContextInterface>()
|
||||
->map_builder()
|
||||
.pose_graph()
|
||||
->DeleteTrajectory(request.trajectory_id());
|
||||
// TODO(gaschler): Think if LocalSlamUploader needs to be notified.
|
||||
Send(common::make_unique<google::protobuf::Empty>());
|
||||
}
|
||||
|
||||
} // namespace handlers
|
||||
} // namespace cloud
|
||||
} // namespace cartographer
|
|
@ -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.
|
||||
*/
|
||||
|
||||
#ifndef CARTOGRAPHER_CLOUD_INTERNAL_HANDLERS_DELETE_TRAJECTORY_HANDLER_H
|
||||
#define CARTOGRAPHER_CLOUD_INTERNAL_HANDLERS_DELETE_TRAJECTORY_HANDLER_H
|
||||
|
||||
#include "async_grpc/rpc_handler.h"
|
||||
#include "cartographer/cloud/proto/map_builder_service.pb.h"
|
||||
#include "google/protobuf/empty.pb.h"
|
||||
|
||||
namespace cartographer {
|
||||
namespace cloud {
|
||||
namespace handlers {
|
||||
|
||||
DEFINE_HANDLER_SIGNATURE(
|
||||
DeleteTrajectorySignature, proto::DeleteTrajectoryRequest,
|
||||
google::protobuf::Empty,
|
||||
"/cartographer.cloud.proto.MapBuilderService/DeleteTrajectory")
|
||||
|
||||
class DeleteTrajectoryHandler
|
||||
: public async_grpc::RpcHandler<DeleteTrajectorySignature> {
|
||||
public:
|
||||
void OnRequest(const proto::DeleteTrajectoryRequest& request) override;
|
||||
};
|
||||
|
||||
} // namespace handlers
|
||||
} // namespace cloud
|
||||
} // namespace cartographer
|
||||
|
||||
#endif // CARTOGRAPHER_CLOUD_INTERNAL_HANDLERS_DELETE_TRAJECTORY_HANDLER_H
|
|
@ -23,6 +23,7 @@
|
|||
#include "cartographer/cloud/internal/handlers/add_rangefinder_data_handler.h"
|
||||
#include "cartographer/cloud/internal/handlers/add_sensor_data_batch_handler.h"
|
||||
#include "cartographer/cloud/internal/handlers/add_trajectory_handler.h"
|
||||
#include "cartographer/cloud/internal/handlers/delete_trajectory_handler.h"
|
||||
#include "cartographer/cloud/internal/handlers/finish_trajectory_handler.h"
|
||||
#include "cartographer/cloud/internal/handlers/get_all_submap_poses.h"
|
||||
#include "cartographer/cloud/internal/handlers/get_constraints_handler.h"
|
||||
|
@ -74,6 +75,7 @@ MapBuilderServer::MapBuilderServer(
|
|||
server_builder.RegisterHandler<handlers::AddLandmarkDataHandler>();
|
||||
server_builder.RegisterHandler<handlers::AddSensorDataBatchHandler>();
|
||||
server_builder.RegisterHandler<handlers::FinishTrajectoryHandler>();
|
||||
server_builder.RegisterHandler<handlers::DeleteTrajectoryHandler>();
|
||||
server_builder
|
||||
.RegisterHandler<handlers::ReceiveGlobalSlamOptimizationsHandler>();
|
||||
server_builder.RegisterHandler<handlers::ReceiveLocalSlamResultsHandler>();
|
||||
|
|
|
@ -98,6 +98,10 @@ message FinishTrajectoryRequest {
|
|||
int32 trajectory_id = 1;
|
||||
}
|
||||
|
||||
message DeleteTrajectoryRequest {
|
||||
int32 trajectory_id = 1;
|
||||
}
|
||||
|
||||
message ReceiveLocalSlamResultsRequest {
|
||||
int32 trajectory_id = 1;
|
||||
}
|
||||
|
@ -245,6 +249,9 @@ service MapBuilderService {
|
|||
// i.e. no further sensor data is expected.
|
||||
rpc FinishTrajectory(FinishTrajectoryRequest) returns (google.protobuf.Empty);
|
||||
|
||||
// Deletes a trajectory asynchronously.
|
||||
rpc DeleteTrajectory(DeleteTrajectoryRequest) returns (google.protobuf.Empty);
|
||||
|
||||
// Retrieves a single submap.
|
||||
rpc GetSubmap(GetSubmapRequest) returns (GetSubmapResponse);
|
||||
|
||||
|
|
Loading…
Reference in New Issue