From 894bad397ddf723a57682ab36ebc451ced8dfb2e Mon Sep 17 00:00:00 2001 From: Alexander Belyaev <32522095+pifon2a@users.noreply.github.com> Date: Thu, 25 Jan 2018 12:10:30 +0100 Subject: [PATCH] Rename Landmark->LandmarkObservation. (#847) --- cartographer/sensor/landmark_data.cc | 16 ++++++++-------- cartographer/sensor/landmark_data.h | 4 ++-- cartographer/sensor/landmark_data_test.cc | 23 ++++++++++++----------- cartographer/sensor/proto/sensor.proto | 4 ++-- 4 files changed, 24 insertions(+), 23 deletions(-) diff --git a/cartographer/sensor/landmark_data.cc b/cartographer/sensor/landmark_data.cc index 71555dd..4f9fbc9 100644 --- a/cartographer/sensor/landmark_data.cc +++ b/cartographer/sensor/landmark_data.cc @@ -24,13 +24,13 @@ namespace sensor { proto::LandmarkData ToProto(const LandmarkData& landmark_data) { proto::LandmarkData proto; proto.set_timestamp(common::ToUniversal(landmark_data.time)); - for (const Landmark& landmark : landmark_data.landmarks) { - auto* item = proto.add_landmarks(); - item->set_id(landmark.id); + for (const auto& observation : landmark_data.landmark_observations) { + auto* item = proto.add_landmark_observations(); + item->set_id(observation.id); *item->mutable_landmark_to_tracking_transform() = - transform::ToProto(landmark.landmark_to_tracking_transform); - item->set_translation_weight(landmark.translation_weight); - item->set_rotation_weight(landmark.rotation_weight); + transform::ToProto(observation.landmark_to_tracking_transform); + item->set_translation_weight(observation.translation_weight); + item->set_rotation_weight(observation.rotation_weight); } return proto; } @@ -38,8 +38,8 @@ proto::LandmarkData ToProto(const LandmarkData& landmark_data) { LandmarkData FromProto(const proto::LandmarkData& proto) { LandmarkData landmark_data; landmark_data.time = common::FromUniversal(proto.timestamp()); - for (const auto& item : proto.landmarks()) { - landmark_data.landmarks.push_back({ + for (const auto& item : proto.landmark_observations()) { + landmark_data.landmark_observations.push_back({ item.id(), transform::ToRigid3(item.landmark_to_tracking_transform()), item.translation_weight(), diff --git a/cartographer/sensor/landmark_data.h b/cartographer/sensor/landmark_data.h index c03be2d..ddab8ba 100644 --- a/cartographer/sensor/landmark_data.h +++ b/cartographer/sensor/landmark_data.h @@ -29,7 +29,7 @@ namespace cartographer { namespace sensor { -struct Landmark { +struct LandmarkObservation { std::string id; transform::Rigid3d landmark_to_tracking_transform; double translation_weight; @@ -38,7 +38,7 @@ struct Landmark { struct LandmarkData { common::Time time; - std::vector landmarks; + std::vector landmark_observations; }; // Converts 'landmark_data' to a proto::LandmarkData. diff --git a/cartographer/sensor/landmark_data_test.cc b/cartographer/sensor/landmark_data_test.cc index 112e6ad..0859ab6 100644 --- a/cartographer/sensor/landmark_data_test.cc +++ b/cartographer/sensor/landmark_data_test.cc @@ -30,21 +30,22 @@ namespace { using ::testing::DoubleNear; using ::testing::Field; -::testing::Matcher EqualsLandmark(const Landmark& expected) { +::testing::Matcher EqualsLandmark( + const LandmarkObservation& expected) { return ::testing::AllOf( - Field(&Landmark::id, expected.id), - Field(&Landmark::landmark_to_tracking_transform, + Field(&LandmarkObservation::id, expected.id), + Field(&LandmarkObservation::landmark_to_tracking_transform, transform::IsNearly(expected.landmark_to_tracking_transform, 1e-2)), - Field(&Landmark::translation_weight, + Field(&LandmarkObservation::translation_weight, DoubleNear(expected.translation_weight, 0.01)), - Field(&Landmark::rotation_weight, + Field(&LandmarkObservation::rotation_weight, DoubleNear(expected.rotation_weight, 0.01))); } class LandmarkDataTest : public ::testing::Test { protected: LandmarkDataTest() - : landmarks_( + : observations_( {{ "ID1", transform::Rigid3d(Eigen::Vector3d(1., 1., 1.), @@ -59,16 +60,16 @@ class LandmarkDataTest : public ::testing::Test { 2.f, 4.f, }}) {} - std::vector landmarks_; + std::vector observations_; }; TEST_F(LandmarkDataTest, LandmarkDataToAndFromProto) { - const auto expected = LandmarkData{common::FromUniversal(50), landmarks_}; + const auto expected = LandmarkData{common::FromUniversal(50), observations_}; const auto actual = FromProto(ToProto(expected)); EXPECT_EQ(expected.time, actual.time); - EXPECT_THAT(actual.landmarks, - ElementsAre(EqualsLandmark(expected.landmarks[0]), - EqualsLandmark(expected.landmarks[1]))); + EXPECT_THAT(actual.landmark_observations, + ElementsAre(EqualsLandmark(expected.landmark_observations[0]), + EqualsLandmark(expected.landmark_observations[1]))); } } // namespace diff --git a/cartographer/sensor/proto/sensor.proto b/cartographer/sensor/proto/sensor.proto index b4918a7..175775f 100644 --- a/cartographer/sensor/proto/sensor.proto +++ b/cartographer/sensor/proto/sensor.proto @@ -61,12 +61,12 @@ message FixedFramePoseData { // Proto representation of ::cartographer::sensor::LandmarkData. message LandmarkData { - message Landmark { + message LandmarkObservation { bytes id = 1; transform.proto.Rigid3d landmark_to_tracking_transform = 2; double translation_weight = 3; double rotation_weight = 4; } int64 timestamp = 1; - repeated Landmark landmarks = 2; + repeated LandmarkObservation landmark_observations = 2; }