Rename namespace to testing (#1191)

We commonly use the namespace testing for test helpers,
so rename similar namespaces to "testing" for consistency.
master
gaschler 2018-06-12 15:18:20 +02:00 committed by Wally B. Feed
parent 29f6ea9ea3
commit f79c6afee7
11 changed files with 58 additions and 57 deletions

View File

@ -64,7 +64,7 @@ class ClientServerTest : public ::testing::Test {
MAP_BUILDER_SERVER.server_address = "0.0.0.0:50051"
return MAP_BUILDER_SERVER)text";
auto map_builder_server_parameters =
mapping::test::ResolveLuaParameters(kMapBuilderServerLua);
mapping::testing::ResolveLuaParameters(kMapBuilderServerLua);
map_builder_server_options_ =
CreateMapBuilderServerOptions(map_builder_server_parameters.get());
@ -79,7 +79,7 @@ class ClientServerTest : public ::testing::Test {
MAP_BUILDER_SERVER.upload_batch_size = 1
return MAP_BUILDER_SERVER)text";
auto uploading_map_builder_server_parameters =
mapping::test::ResolveLuaParameters(kUploadingMapBuilderServerLua);
mapping::testing::ResolveLuaParameters(kUploadingMapBuilderServerLua);
uploading_map_builder_server_options_ = CreateMapBuilderServerOptions(
uploading_map_builder_server_parameters.get());
@ -89,7 +89,7 @@ class ClientServerTest : public ::testing::Test {
TRAJECTORY_BUILDER.trajectory_builder_2d.submaps.num_range_data = 4
return TRAJECTORY_BUILDER)text";
auto trajectory_builder_parameters =
mapping::test::ResolveLuaParameters(kTrajectoryBuilderLua);
mapping::testing::ResolveLuaParameters(kTrajectoryBuilderLua);
trajectory_builder_options_ = mapping::CreateTrajectoryBuilderOptions(
trajectory_builder_parameters.get());
number_of_insertion_results_ = 0;
@ -278,7 +278,7 @@ TEST_F(ClientServerTest, LocalSlam2D) {
local_slam_result_callback_);
TrajectoryBuilderInterface* trajectory_stub =
stub_->GetTrajectoryBuilder(trajectory_id);
const auto measurements = mapping::test::GenerateFakeRangeMeasurements(
const auto measurements = mapping::testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (const auto& measurement : measurements) {
trajectory_stub->AddSensorData(kRangeSensorId.id, measurement);
@ -316,7 +316,7 @@ TEST_F(ClientServerTest, GlobalSlam3D) {
local_slam_result_callback_);
TrajectoryBuilderInterface* trajectory_stub =
stub_->GetTrajectoryBuilder(trajectory_id);
const auto measurements = mapping::test::GenerateFakeRangeMeasurements(
const auto measurements = mapping::testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (const auto& measurement : measurements) {
sensor::ImuData imu_data{
@ -381,7 +381,7 @@ TEST_F(ClientServerTest, LocalSlam2DWithUploadingServer) {
local_slam_result_callback_);
TrajectoryBuilderInterface* trajectory_stub =
stub_for_uploading_server_->GetTrajectoryBuilder(trajectory_id);
const auto measurements = mapping::test::GenerateFakeRangeMeasurements(
const auto measurements = mapping::testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (const auto& measurement : measurements) {
trajectory_stub->AddSensorData(kRangeSensorId.id, measurement);

View File

@ -63,7 +63,7 @@ class PoseGraph3DTest : public ::testing::Test {
const std::string kPoseGraphLua = R"text(
include "pose_graph.lua"
return POSE_GRAPH)text";
auto pose_graph_parameters = test::ResolveLuaParameters(kPoseGraphLua);
auto pose_graph_parameters = testing::ResolveLuaParameters(kPoseGraphLua);
pose_graph_options_ = CreatePoseGraphOptions(pose_graph_parameters.get());
}
@ -107,17 +107,17 @@ TEST_F(PoseGraph3DTest, Empty) {
TEST_F(PoseGraph3DTest, BasicSerialization) {
BuildPoseGraph();
proto::PoseGraph proto;
auto fake_node = test::CreateFakeNode();
test::AddToProtoGraph(fake_node, &proto);
auto fake_node = testing::CreateFakeNode();
testing::AddToProtoGraph(fake_node, &proto);
pose_graph_->AddNodeFromProto(Rigid3d::Identity(), fake_node);
auto fake_submap = test::CreateFakeSubmap3D();
test::AddToProtoGraph(fake_submap, &proto);
auto fake_submap = testing::CreateFakeSubmap3D();
testing::AddToProtoGraph(fake_submap, &proto);
pose_graph_->AddSubmapFromProto(Rigid3d::Identity(), fake_submap);
test::AddToProtoGraph(test::CreateFakeConstraint(fake_node, fake_submap),
&proto);
testing::AddToProtoGraph(
testing::CreateFakeConstraint(fake_node, fake_submap), &proto);
pose_graph_->AddSerializedConstraints(FromProto(proto.constraint()));
test::AddToProtoGraph(
test::CreateFakeLandmark("landmark_id", Rigid3d::Identity()), &proto);
testing::AddToProtoGraph(
testing::CreateFakeLandmark("landmark_id", Rigid3d::Identity()), &proto);
pose_graph_->SetLandmarkPose("landmark_id", Rigid3d::Identity());
pose_graph_->WaitForAllComputations();
proto::PoseGraph actual_proto = pose_graph_->ToProto();
@ -143,18 +143,18 @@ TEST_F(PoseGraph3DTest, PureLocalizationTrimmer) {
const int num_nodes_per_submap = 2;
for (int i = 0; i < num_submaps_to_create; ++i) {
int submap_index = (i < 3) ? 42 + i : 100 + i;
auto submap = test::CreateFakeSubmap3D(trajectory_id, submap_index);
auto submap = testing::CreateFakeSubmap3D(trajectory_id, submap_index);
pose_graph_->AddSubmapFromProto(Rigid3d::Identity(), submap);
for (int j = 0; j < num_nodes_per_submap; ++j) {
int node_index = 7 + num_nodes_per_submap * submap_index + j;
auto node = test::CreateFakeNode(trajectory_id, node_index);
auto node = testing::CreateFakeNode(trajectory_id, node_index);
pose_graph_->AddNodeFromProto(Rigid3d::Identity(), node);
proto::PoseGraph proto;
auto constraint = test::CreateFakeConstraint(node, submap);
auto constraint = testing::CreateFakeConstraint(node, submap);
// TODO(gaschler): Also remove inter constraints when all references are
// gone.
constraint.set_tag(proto::PoseGraph::Constraint::INTRA_SUBMAP);
test::AddToProtoGraph(constraint, &proto);
testing::AddToProtoGraph(constraint, &proto);
pose_graph_->AddSerializedConstraints(FromProto(proto.constraint()));
}
}
@ -222,16 +222,16 @@ TEST_F(PoseGraph3DTest, EvenSubmapTrimmer) {
const int num_nodes_per_submap = 3;
for (int i = 0; i < num_submaps_to_create; ++i) {
int submap_index = 42 + i;
auto submap = test::CreateFakeSubmap3D(trajectory_id, submap_index);
auto submap = testing::CreateFakeSubmap3D(trajectory_id, submap_index);
pose_graph_->AddSubmapFromProto(Rigid3d::Identity(), submap);
for (int j = 0; j < num_nodes_per_submap; ++j) {
int node_index = 7 + num_nodes_per_submap * i + j;
auto node = test::CreateFakeNode(trajectory_id, node_index);
auto node = testing::CreateFakeNode(trajectory_id, node_index);
pose_graph_->AddNodeFromProto(Rigid3d::Identity(), node);
proto::PoseGraph proto;
auto constraint = test::CreateFakeConstraint(node, submap);
auto constraint = testing::CreateFakeConstraint(node, submap);
constraint.set_tag(proto::PoseGraph::Constraint::INTRA_SUBMAP);
test::AddToProtoGraph(constraint, &proto);
testing::AddToProtoGraph(constraint, &proto);
pose_graph_->AddSerializedConstraints(FromProto(proto.constraint()));
}
}

View File

@ -39,7 +39,7 @@ class MockCallback {
class ConstraintBuilder2DTest : public ::testing::Test {
protected:
void SetUp() override {
auto constraint_builder_parameters = test::ResolveLuaParameters(R"text(
auto constraint_builder_parameters = testing::ResolveLuaParameters(R"text(
include "pose_graph.lua"
POSE_GRAPH.constraint_builder.sampling_ratio = 1
POSE_GRAPH.constraint_builder.min_score = 0
@ -57,7 +57,7 @@ class ConstraintBuilder2DTest : public ::testing::Test {
TEST_F(ConstraintBuilder2DTest, CallsBack) {
EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), 0);
EXPECT_CALL(mock_, Run(testing::IsEmpty()));
EXPECT_CALL(mock_, Run(::testing::IsEmpty()));
constraint_builder_->NotifyEndOfNode();
constraint_builder_->WhenDone(
std::bind(&MockCallback::Run, &mock_, std::placeholders::_1));
@ -92,9 +92,9 @@ TEST_F(ConstraintBuilder2DTest, FindsConstraints) {
thread_pool_.WaitUntilIdle();
EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), ++expected_nodes);
EXPECT_CALL(mock_,
Run(testing::AllOf(
testing::SizeIs(3),
testing::Each(testing::Field(
Run(::testing::AllOf(
::testing::SizeIs(3),
::testing::Each(::testing::Field(
&PoseGraphInterface::Constraint::tag,
PoseGraphInterface::Constraint::INTER_SUBMAP)))));
constraint_builder_->WhenDone(

View File

@ -40,7 +40,7 @@ class MockCallback {
class ConstraintBuilder3DTest : public ::testing::Test {
protected:
void SetUp() override {
auto constraint_builder_parameters = test::ResolveLuaParameters(R"text(
auto constraint_builder_parameters = testing::ResolveLuaParameters(R"text(
include "pose_graph.lua"
POSE_GRAPH.constraint_builder.sampling_ratio = 1
POSE_GRAPH.constraint_builder.min_score = 0
@ -60,7 +60,7 @@ class ConstraintBuilder3DTest : public ::testing::Test {
TEST_F(ConstraintBuilder3DTest, CallsBack) {
EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), 0);
EXPECT_CALL(mock_, Run(testing::IsEmpty()));
EXPECT_CALL(mock_, Run(::testing::IsEmpty()));
constraint_builder_->NotifyEndOfNode();
constraint_builder_->WhenDone(
std::bind(&MockCallback::Run, &mock_, std::placeholders::_1));
@ -100,9 +100,9 @@ TEST_F(ConstraintBuilder3DTest, FindsConstraints) {
thread_pool_.WaitUntilIdle();
EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), ++expected_nodes);
EXPECT_CALL(mock_,
Run(testing::AllOf(
testing::SizeIs(3),
testing::Each(testing::Field(
Run(::testing::AllOf(
::testing::SizeIs(3),
::testing::Each(::testing::Field(
&PoseGraphInterface::Constraint::tag,
PoseGraphInterface::Constraint::INTER_SUBMAP)))));
constraint_builder_->WhenDone(

View File

@ -25,7 +25,7 @@
namespace cartographer {
namespace mapping {
namespace test {
namespace testing {
std::unique_ptr<::cartographer::common::LuaParameterDictionary>
ResolveLuaParameters(const std::string& lua_code) {
@ -171,6 +171,6 @@ void AddToProtoGraph(const proto::PoseGraph::LandmarkPose& landmark,
*pose_graph->add_landmark_poses() = landmark;
}
} // namespace test
} // namespace testing
} // namespace mapping
} // namespace cartographer

View File

@ -25,7 +25,7 @@
namespace cartographer {
namespace mapping {
namespace test {
namespace testing {
std::unique_ptr<::cartographer::common::LuaParameterDictionary>
ResolveLuaParameters(const std::string& lua_code);
@ -63,7 +63,7 @@ void AddToProtoGraph(const proto::PoseGraph::Constraint& constraint,
void AddToProtoGraph(const proto::PoseGraph::LandmarkPose& landmark_node,
proto::PoseGraph* pose_graph);
} // namespace test
} // namespace testing
} // namespace mapping
} // namespace cartographer

View File

@ -45,7 +45,7 @@ class MapBuilderTest : public ::testing::Test {
MAP_BUILDER.pose_graph.global_sampling_ratio = 0.05
MAP_BUILDER.pose_graph.global_constraint_search_after_n_seconds = 0
return MAP_BUILDER)text";
auto map_builder_parameters = test::ResolveLuaParameters(kMapBuilderLua);
auto map_builder_parameters = testing::ResolveLuaParameters(kMapBuilderLua);
map_builder_options_ =
CreateMapBuilderOptions(map_builder_parameters.get());
// Multiple submaps are created because of a small 'num_range_data'.
@ -56,7 +56,7 @@ class MapBuilderTest : public ::testing::Test {
TRAJECTORY_BUILDER.trajectory_builder_3d.submaps.num_range_data = 4
return TRAJECTORY_BUILDER)text";
auto trajectory_builder_parameters =
test::ResolveLuaParameters(kTrajectoryBuilderLua);
testing::ResolveLuaParameters(kTrajectoryBuilderLua);
trajectory_builder_options_ =
CreateTrajectoryBuilderOptions(trajectory_builder_parameters.get());
}
@ -95,7 +95,7 @@ class MapBuilderTest : public ::testing::Test {
GetLocalSlamResultCallback());
TrajectoryBuilderInterface* trajectory_builder =
map_builder_->GetTrajectoryBuilder(trajectory_id);
auto measurements = test::GenerateFakeRangeMeasurements(
auto measurements = testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (auto& measurement : measurements) {
trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
@ -144,7 +144,7 @@ TEST_F(MapBuilderTest, LocalSlam2D) {
GetLocalSlamResultCallback());
TrajectoryBuilderInterface* trajectory_builder =
map_builder_->GetTrajectoryBuilder(trajectory_id);
const auto measurements = test::GenerateFakeRangeMeasurements(
const auto measurements = testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (const auto& measurement : measurements) {
trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
@ -167,7 +167,7 @@ TEST_F(MapBuilderTest, LocalSlam3D) {
GetLocalSlamResultCallback());
TrajectoryBuilderInterface* trajectory_builder =
map_builder_->GetTrajectoryBuilder(trajectory_id);
const auto measurements = test::GenerateFakeRangeMeasurements(
const auto measurements = testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (const auto& measurement : measurements) {
trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
@ -194,7 +194,7 @@ TEST_F(MapBuilderTest, GlobalSlam2D) {
GetLocalSlamResultCallback());
TrajectoryBuilderInterface* trajectory_builder =
map_builder_->GetTrajectoryBuilder(trajectory_id);
const auto measurements = test::GenerateFakeRangeMeasurements(
const auto measurements = testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (const auto& measurement : measurements) {
trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
@ -209,7 +209,7 @@ TEST_F(MapBuilderTest, GlobalSlam2D) {
0.1 * kTravelDistance);
EXPECT_GE(map_builder_->pose_graph()->constraints().size(), 50);
EXPECT_THAT(map_builder_->pose_graph()->constraints(),
testing::Contains(testing::Field(
::testing::Contains(::testing::Field(
&PoseGraphInterface::Constraint::tag,
PoseGraphInterface::Constraint::INTER_SUBMAP)));
const auto trajectory_nodes =
@ -233,7 +233,7 @@ TEST_F(MapBuilderTest, GlobalSlam3D) {
GetLocalSlamResultCallback());
TrajectoryBuilderInterface* trajectory_builder =
map_builder_->GetTrajectoryBuilder(trajectory_id);
const auto measurements = test::GenerateFakeRangeMeasurements(
const auto measurements = testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (const auto& measurement : measurements) {
trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
@ -252,7 +252,7 @@ TEST_F(MapBuilderTest, GlobalSlam3D) {
0.1 * kTravelDistance);
EXPECT_GE(map_builder_->pose_graph()->constraints().size(), 10);
EXPECT_THAT(map_builder_->pose_graph()->constraints(),
testing::Contains(testing::Field(
::testing::Contains(::testing::Field(
&PoseGraphInterface::Constraint::tag,
PoseGraphInterface::Constraint::INTER_SUBMAP)));
const auto trajectory_nodes =
@ -280,7 +280,7 @@ TEST_F(MapBuilderTest, SaveLoadState) {
GetLocalSlamResultCallback());
TrajectoryBuilderInterface* trajectory_builder =
map_builder_->GetTrajectoryBuilder(trajectory_id);
const auto measurements = test::GenerateFakeRangeMeasurements(
const auto measurements = testing::GenerateFakeRangeMeasurements(
kTravelDistance, kDuration, kTimeStep);
for (const auto& measurement : measurements) {
trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
@ -353,7 +353,7 @@ TEST_F(MapBuilderTest, LocalizationOnFrozenTrajectory2D) {
Eigen::Quaterniond(Eigen::AngleAxisd(1.2, Eigen::Vector3d::UnitZ())));
Eigen::Vector3d travel_translation =
Eigen::Vector3d(2., 1., 0.).normalized() * kTravelDistance;
auto measurements = test::GenerateFakeRangeMeasurements(
auto measurements = testing::GenerateFakeRangeMeasurements(
travel_translation.cast<float>(), kDuration, kTimeStep,
frozen_trajectory_to_global.cast<float>());
for (auto& measurement : measurements) {
@ -380,7 +380,7 @@ TEST_F(MapBuilderTest, LocalizationOnFrozenTrajectory2D) {
EXPECT_GT(num_cross_trajectory_constraints, 3);
// TODO(gaschler): Subscribe global slam callback, verify that all nodes are
// optimized.
EXPECT_THAT(constraints, testing::Contains(testing::Field(
EXPECT_THAT(constraints, ::testing::Contains(::testing::Field(
&PoseGraphInterface::Constraint::tag,
PoseGraphInterface::Constraint::INTER_SUBMAP)));
const auto trajectory_nodes =

View File

@ -27,8 +27,9 @@ namespace mapping {
namespace {
TEST(PoseGraph, SerializeConstraint) {
proto::PoseGraph::Constraint expected_constraint = test::CreateFakeConstraint(
test::CreateFakeNode(1, 2), test::CreateFakeSubmap3D(2, 3));
proto::PoseGraph::Constraint expected_constraint =
testing::CreateFakeConstraint(testing::CreateFakeNode(1, 2),
testing::CreateFakeSubmap3D(2, 3));
::google::protobuf::RepeatedPtrField<proto::PoseGraph::Constraint>
constraint_protos;
*constraint_protos.Add() = expected_constraint;

View File

@ -31,8 +31,8 @@ namespace cartographer {
namespace sensor {
namespace {
using test::CollatorInput;
using test::CollatorOutput;
using testing::CollatorInput;
using testing::CollatorOutput;
TEST(Collator, Ordering) {
const int kTrajectoryId = 0;

View File

@ -36,7 +36,7 @@ MATCHER_P(Near, point, std::string(negation ? "Doesn't" : "Does") + " match.") {
return arg.isApprox(point, 0.001f);
}
namespace test {
namespace testing {
typedef std::tuple<int /* trajectory_id */, std::string /* sensor_id */,
common::Time>
@ -80,7 +80,7 @@ struct CollatorInput {
const CollatorOutput expected_output;
};
} // namespace test
} // namespace testing
} // namespace sensor
} // namespace cartographer

View File

@ -31,8 +31,8 @@ namespace cartographer {
namespace sensor {
namespace {
using test::CollatorInput;
using test::CollatorOutput;
using testing::CollatorInput;
using testing::CollatorOutput;
TEST(TrajectoryCollator, OrderingMultipleTrajectories) {
const int kTrajectoryId[] = {4, 7};