Rename Landmark->LandmarkObservation. (#847)

master
Alexander Belyaev 2018-01-25 12:10:30 +01:00 committed by GitHub
parent 37ddf9e550
commit 894bad397d
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
4 changed files with 24 additions and 23 deletions

View File

@ -24,13 +24,13 @@ namespace sensor {
proto::LandmarkData ToProto(const LandmarkData& landmark_data) { proto::LandmarkData ToProto(const LandmarkData& landmark_data) {
proto::LandmarkData proto; proto::LandmarkData proto;
proto.set_timestamp(common::ToUniversal(landmark_data.time)); proto.set_timestamp(common::ToUniversal(landmark_data.time));
for (const Landmark& landmark : landmark_data.landmarks) { for (const auto& observation : landmark_data.landmark_observations) {
auto* item = proto.add_landmarks(); auto* item = proto.add_landmark_observations();
item->set_id(landmark.id); item->set_id(observation.id);
*item->mutable_landmark_to_tracking_transform() = *item->mutable_landmark_to_tracking_transform() =
transform::ToProto(landmark.landmark_to_tracking_transform); transform::ToProto(observation.landmark_to_tracking_transform);
item->set_translation_weight(landmark.translation_weight); item->set_translation_weight(observation.translation_weight);
item->set_rotation_weight(landmark.rotation_weight); item->set_rotation_weight(observation.rotation_weight);
} }
return proto; return proto;
} }
@ -38,8 +38,8 @@ proto::LandmarkData ToProto(const LandmarkData& landmark_data) {
LandmarkData FromProto(const proto::LandmarkData& proto) { LandmarkData FromProto(const proto::LandmarkData& proto) {
LandmarkData landmark_data; LandmarkData landmark_data;
landmark_data.time = common::FromUniversal(proto.timestamp()); landmark_data.time = common::FromUniversal(proto.timestamp());
for (const auto& item : proto.landmarks()) { for (const auto& item : proto.landmark_observations()) {
landmark_data.landmarks.push_back({ landmark_data.landmark_observations.push_back({
item.id(), item.id(),
transform::ToRigid3(item.landmark_to_tracking_transform()), transform::ToRigid3(item.landmark_to_tracking_transform()),
item.translation_weight(), item.translation_weight(),

View File

@ -29,7 +29,7 @@
namespace cartographer { namespace cartographer {
namespace sensor { namespace sensor {
struct Landmark { struct LandmarkObservation {
std::string id; std::string id;
transform::Rigid3d landmark_to_tracking_transform; transform::Rigid3d landmark_to_tracking_transform;
double translation_weight; double translation_weight;
@ -38,7 +38,7 @@ struct Landmark {
struct LandmarkData { struct LandmarkData {
common::Time time; common::Time time;
std::vector<Landmark> landmarks; std::vector<LandmarkObservation> landmark_observations;
}; };
// Converts 'landmark_data' to a proto::LandmarkData. // Converts 'landmark_data' to a proto::LandmarkData.

View File

@ -30,21 +30,22 @@ namespace {
using ::testing::DoubleNear; using ::testing::DoubleNear;
using ::testing::Field; using ::testing::Field;
::testing::Matcher<const Landmark&> EqualsLandmark(const Landmark& expected) { ::testing::Matcher<const LandmarkObservation&> EqualsLandmark(
const LandmarkObservation& expected) {
return ::testing::AllOf( return ::testing::AllOf(
Field(&Landmark::id, expected.id), Field(&LandmarkObservation::id, expected.id),
Field(&Landmark::landmark_to_tracking_transform, Field(&LandmarkObservation::landmark_to_tracking_transform,
transform::IsNearly(expected.landmark_to_tracking_transform, 1e-2)), transform::IsNearly(expected.landmark_to_tracking_transform, 1e-2)),
Field(&Landmark::translation_weight, Field(&LandmarkObservation::translation_weight,
DoubleNear(expected.translation_weight, 0.01)), DoubleNear(expected.translation_weight, 0.01)),
Field(&Landmark::rotation_weight, Field(&LandmarkObservation::rotation_weight,
DoubleNear(expected.rotation_weight, 0.01))); DoubleNear(expected.rotation_weight, 0.01)));
} }
class LandmarkDataTest : public ::testing::Test { class LandmarkDataTest : public ::testing::Test {
protected: protected:
LandmarkDataTest() LandmarkDataTest()
: landmarks_( : observations_(
{{ {{
"ID1", "ID1",
transform::Rigid3d(Eigen::Vector3d(1., 1., 1.), transform::Rigid3d(Eigen::Vector3d(1., 1., 1.),
@ -59,16 +60,16 @@ class LandmarkDataTest : public ::testing::Test {
2.f, 2.f,
4.f, 4.f,
}}) {} }}) {}
std::vector<Landmark> landmarks_; std::vector<LandmarkObservation> observations_;
}; };
TEST_F(LandmarkDataTest, LandmarkDataToAndFromProto) { 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)); const auto actual = FromProto(ToProto(expected));
EXPECT_EQ(expected.time, actual.time); EXPECT_EQ(expected.time, actual.time);
EXPECT_THAT(actual.landmarks, EXPECT_THAT(actual.landmark_observations,
ElementsAre(EqualsLandmark(expected.landmarks[0]), ElementsAre(EqualsLandmark(expected.landmark_observations[0]),
EqualsLandmark(expected.landmarks[1]))); EqualsLandmark(expected.landmark_observations[1])));
} }
} // namespace } // namespace

View File

@ -61,12 +61,12 @@ message FixedFramePoseData {
// Proto representation of ::cartographer::sensor::LandmarkData. // Proto representation of ::cartographer::sensor::LandmarkData.
message LandmarkData { message LandmarkData {
message Landmark { message LandmarkObservation {
bytes id = 1; bytes id = 1;
transform.proto.Rigid3d landmark_to_tracking_transform = 2; transform.proto.Rigid3d landmark_to_tracking_transform = 2;
double translation_weight = 3; double translation_weight = 3;
double rotation_weight = 4; double rotation_weight = 4;
} }
int64 timestamp = 1; int64 timestamp = 1;
repeated Landmark landmarks = 2; repeated LandmarkObservation landmark_observations = 2;
} }