add_trajectory_handler_test.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/cloud/internal/handlers/add_trajectory_handler.h"
00018 
00019 #include "cartographer/cloud/internal/sensor/serialization.h"
00020 #include "cartographer/cloud/internal/testing/handler_test.h"
00021 #include "cartographer/cloud/internal/testing/test_helpers.h"
00022 #include "cartographer/mapping/internal/testing/mock_map_builder.h"
00023 #include "google/protobuf/text_format.h"
00024 #include "gtest/gtest.h"
00025 
00026 namespace cartographer {
00027 namespace cloud {
00028 namespace handlers {
00029 namespace {
00030 
00031 using ::testing::_;
00032 using ::testing::ContainerEq;
00033 using ::testing::Eq;
00034 using ::testing::Return;
00035 using ::testing::ReturnRef;
00036 using ::testing::Test;
00037 using ::testing::Truly;
00038 
00039 const std::string kMessage = R"(
00040     client_id: "CLIENT_ID"
00041     expected_sensor_ids {
00042       id: "range_sensor"
00043       type: RANGE
00044     }
00045     expected_sensor_ids {
00046       id: "imu_sensor"
00047       type: IMU
00048     }
00049     trajectory_builder_options {
00050       trajectory_builder_2d_options {
00051         min_range: 20
00052         max_range: 30
00053       }
00054       pure_localization_trimmer {
00055         max_submaps_to_keep: 3
00056       }
00057       initial_trajectory_pose {
00058         relative_pose {
00059           translation {
00060             x: 1 y: 2 z: 3
00061           }
00062           rotation {
00063             w: 4 x: 5 y: 6 z: 7
00064           }
00065         }
00066         to_trajectory_id: 8
00067         timestamp: 9
00068       }
00069     }
00070   )";
00071 
00072 class AddTrajectoryHandlerTest
00073     : public testing::HandlerTest<AddTrajectorySignature,
00074                                   AddTrajectoryHandler> {
00075  public:
00076   void SetUp() override {
00077     testing::HandlerTest<AddTrajectorySignature, AddTrajectoryHandler>::SetUp();
00078     mock_map_builder_ = absl::make_unique<mapping::testing::MockMapBuilder>();
00079     EXPECT_CALL(*mock_map_builder_context_,
00080                 GetLocalSlamResultCallbackForSubscriptions())
00081         .WillOnce(Return(nullptr));
00082     EXPECT_CALL(*mock_map_builder_context_, map_builder())
00083         .WillOnce(ReturnRef(*mock_map_builder_));
00084   }
00085 
00086  protected:
00087   std::set<mapping::TrajectoryBuilderInterface::SensorId> ParseSensorIds(
00088       const proto::AddTrajectoryRequest &request) {
00089     std::set<mapping::TrajectoryBuilderInterface::SensorId> expected_sensor_ids;
00090     for (const auto &sensor_id : request.expected_sensor_ids()) {
00091       expected_sensor_ids.insert(cloud::FromProto(sensor_id));
00092     }
00093     return expected_sensor_ids;
00094   }
00095 
00096   std::unique_ptr<mapping::testing::MockMapBuilder> mock_map_builder_;
00097 };
00098 
00099 TEST_F(AddTrajectoryHandlerTest, NoLocalSlamUploader) {
00100   SetNoLocalTrajectoryUploader();
00101   proto::AddTrajectoryRequest request;
00102   EXPECT_TRUE(
00103       google::protobuf::TextFormat::ParseFromString(kMessage, &request));
00104   EXPECT_CALL(*mock_map_builder_,
00105               AddTrajectoryBuilder(ContainerEq(ParseSensorIds(request)),
00106                                    Truly(testing::BuildProtoPredicateEquals(
00107                                        &request.trajectory_builder_options())),
00108                                    _))
00109       .WillOnce(Return(13));
00110   EXPECT_CALL(*mock_map_builder_context_,
00111               RegisterClientIdForTrajectory(Eq("CLIENT_ID"), Eq(13)));
00112   test_server_->SendWrite(request);
00113   EXPECT_EQ(test_server_->response().trajectory_id(), 13);
00114 }
00115 
00116 TEST_F(AddTrajectoryHandlerTest, WithLocalSlamUploader) {
00117   SetMockLocalTrajectoryUploader();
00118   proto::AddTrajectoryRequest request;
00119   EXPECT_TRUE(
00120       google::protobuf::TextFormat::ParseFromString(kMessage, &request));
00121   EXPECT_CALL(*mock_map_builder_,
00122               AddTrajectoryBuilder(ContainerEq(ParseSensorIds(request)),
00123                                    Truly(testing::BuildProtoPredicateEquals(
00124                                        &request.trajectory_builder_options())),
00125                                    _))
00126       .WillOnce(Return(13));
00127   EXPECT_CALL(*mock_map_builder_context_,
00128               RegisterClientIdForTrajectory(Eq("CLIENT_ID"), Eq(13)));
00129   auto upstream_trajectory_builder_options =
00130       request.trajectory_builder_options();
00131   // Reproduce the changes to the request as done by the handler.
00132   upstream_trajectory_builder_options.clear_trajectory_builder_2d_options();
00133   upstream_trajectory_builder_options.clear_trajectory_builder_3d_options();
00134   upstream_trajectory_builder_options.clear_pure_localization_trimmer();
00135   upstream_trajectory_builder_options.clear_initial_trajectory_pose();
00136   EXPECT_CALL(*mock_local_trajectory_uploader_,
00137               AddTrajectory(Eq("CLIENT_ID"), Eq(13), ParseSensorIds(request),
00138                             Truly(testing::BuildProtoPredicateEquals(
00139                                 &upstream_trajectory_builder_options))))
00140       .WillOnce(Return(grpc::Status::OK));
00141   test_server_->SendWrite(request);
00142   EXPECT_EQ(test_server_->response().trajectory_id(), 13);
00143 }
00144 
00145 }  // namespace
00146 }  // namespace handlers
00147 }  // namespace cloud
00148 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35