Return the proto from Submap::ToProto instead of passing pointer. (#1294)

Submap::ToProto now returns the proto. 

This PR makes the interfaces for serialization more consistent: In `mapping_state_serialization.cc` all `ToProto` methods return the proto except Submap::ToProto.
master
Martin Schwörer 2018-07-20 15:16:44 +02:00 committed by Wally B. Feed
parent 2de0e5f04b
commit f1ac896729
9 changed files with 21 additions and 21 deletions

View File

@ -92,7 +92,7 @@ void CreateSensorDataForLocalSlamResult(
for (const auto& insertion_submap : insertion_result.insertion_submaps) { for (const auto& insertion_submap : insertion_result.insertion_submaps) {
// We only send the probability grid up if the submap is finished. // We only send the probability grid up if the submap is finished.
auto* submap = proto->mutable_local_slam_result_data()->add_submaps(); auto* submap = proto->mutable_local_slam_result_data()->add_submaps();
insertion_submap->ToProto(submap, insertion_submap->finished()); *submap = insertion_submap->ToProto(insertion_submap->finished());
submap->mutable_submap_id()->set_trajectory_id(trajectory_id); submap->mutable_submap_id()->set_trajectory_id(trajectory_id);
submap->mutable_submap_id()->set_submap_index(starting_submap_index); submap->mutable_submap_id()->set_submap_index(starting_submap_index);
++starting_submap_index; ++starting_submap_index;

View File

@ -84,14 +84,13 @@ void SerializeSubmaps(
for (const auto& submap_id_data : submap_data) { for (const auto& submap_id_data : submap_data) {
SerializedData proto; SerializedData proto;
auto* const submap_proto = proto.mutable_submap(); auto* const submap_proto = proto.mutable_submap();
*submap_proto = submap_id_data.data.submap->ToProto(
/*include_probability_grid_data=*/submap_id_data.data.submap
->finished());
submap_proto->mutable_submap_id()->set_trajectory_id( submap_proto->mutable_submap_id()->set_trajectory_id(
submap_id_data.id.trajectory_id); submap_id_data.id.trajectory_id);
submap_proto->mutable_submap_id()->set_submap_index( submap_proto->mutable_submap_id()->set_submap_index(
submap_id_data.id.submap_index); submap_id_data.id.submap_index);
submap_id_data.data.submap->ToProto(
submap_proto,
/*include_probability_grid_data=*/submap_id_data.data.submap
->finished());
writer->WriteProto(proto); writer->WriteProto(proto);
} }
} }

View File

@ -82,9 +82,10 @@ Submap2D::Submap2D(const proto::Submap2D& proto,
set_finished(proto.finished()); set_finished(proto.finished());
} }
void Submap2D::ToProto(proto::Submap* const proto, proto::Submap Submap2D::ToProto(
bool include_probability_grid_data) const { const bool include_probability_grid_data) const {
auto* const submap_2d = proto->mutable_submap_2d(); proto::Submap proto;
auto* const submap_2d = proto.mutable_submap_2d();
*submap_2d->mutable_local_pose() = transform::ToProto(local_pose()); *submap_2d->mutable_local_pose() = transform::ToProto(local_pose());
submap_2d->set_num_range_data(num_range_data()); submap_2d->set_num_range_data(num_range_data());
submap_2d->set_finished(finished()); submap_2d->set_finished(finished());
@ -92,6 +93,7 @@ void Submap2D::ToProto(proto::Submap* const proto,
CHECK(grid_); CHECK(grid_);
*submap_2d->mutable_grid() = grid_->ToProto(); *submap_2d->mutable_grid() = grid_->ToProto();
} }
return proto;
} }
void Submap2D::UpdateFromProto(const proto::Submap& proto) { void Submap2D::UpdateFromProto(const proto::Submap& proto) {

View File

@ -47,8 +47,7 @@ class Submap2D : public Submap {
explicit Submap2D(const proto::Submap2D& proto, explicit Submap2D(const proto::Submap2D& proto,
ValueConversionTables* conversion_tables); ValueConversionTables* conversion_tables);
void ToProto(proto::Submap* proto, proto::Submap ToProto(bool include_probability_grid_data) const override;
bool include_probability_grid_data) const override;
void UpdateFromProto(const proto::Submap& proto) override; void UpdateFromProto(const proto::Submap& proto) override;
void ToResponseProto(const transform::Rigid3d& global_submap_pose, void ToResponseProto(const transform::Rigid3d& global_submap_pose,

View File

@ -103,8 +103,8 @@ TEST(Submap2DTest, ToFromProto) {
common::make_unique<ProbabilityGrid>(expected_map_limits, common::make_unique<ProbabilityGrid>(expected_map_limits,
&conversion_tables), &conversion_tables),
&conversion_tables); &conversion_tables);
proto::Submap proto; const proto::Submap proto =
expected.ToProto(&proto, true /* include_probability_grid_data */); expected.ToProto(true /* include_probability_grid_data */);
EXPECT_TRUE(proto.has_submap_2d()); EXPECT_TRUE(proto.has_submap_2d());
EXPECT_FALSE(proto.has_submap_3d()); EXPECT_FALSE(proto.has_submap_3d());
const auto actual = Submap2D(proto.submap_2d(), &conversion_tables); const auto actual = Submap2D(proto.submap_2d(), &conversion_tables);

View File

@ -213,9 +213,10 @@ Submap3D::Submap3D(const proto::Submap3D& proto)
set_finished(proto.finished()); set_finished(proto.finished());
} }
void Submap3D::ToProto(proto::Submap* const proto, proto::Submap Submap3D::ToProto(
bool include_probability_grid_data) const { const bool include_probability_grid_data) const {
auto* const submap_3d = proto->mutable_submap_3d(); proto::Submap proto;
auto* const submap_3d = proto.mutable_submap_3d();
*submap_3d->mutable_local_pose() = transform::ToProto(local_pose()); *submap_3d->mutable_local_pose() = transform::ToProto(local_pose());
submap_3d->set_num_range_data(num_range_data()); submap_3d->set_num_range_data(num_range_data());
submap_3d->set_finished(finished()); submap_3d->set_finished(finished());
@ -225,6 +226,7 @@ void Submap3D::ToProto(proto::Submap* const proto,
*submap_3d->mutable_low_resolution_hybrid_grid() = *submap_3d->mutable_low_resolution_hybrid_grid() =
low_resolution_hybrid_grid().ToProto(); low_resolution_hybrid_grid().ToProto();
} }
return proto;
} }
void Submap3D::UpdateFromProto(const proto::Submap& proto) { void Submap3D::UpdateFromProto(const proto::Submap& proto) {

View File

@ -46,8 +46,7 @@ class Submap3D : public Submap {
const transform::Rigid3d& local_submap_pose); const transform::Rigid3d& local_submap_pose);
explicit Submap3D(const proto::Submap3D& proto); explicit Submap3D(const proto::Submap3D& proto);
void ToProto(proto::Submap* proto, proto::Submap ToProto(bool include_probability_grid_data) const override;
bool include_probability_grid_data) const override;
void UpdateFromProto(const proto::Submap& proto) override; void UpdateFromProto(const proto::Submap& proto) override;
void ToResponseProto(const transform::Rigid3d& global_submap_pose, void ToResponseProto(const transform::Rigid3d& global_submap_pose,

View File

@ -28,8 +28,8 @@ TEST(SubmapsTest, ToFromProto) {
0.05, 0.25, 0.05, 0.25,
transform::Rigid3d(Eigen::Vector3d(1., 2., 0.), transform::Rigid3d(Eigen::Vector3d(1., 2., 0.),
Eigen::Quaterniond(0., 0., 0., 1.))); Eigen::Quaterniond(0., 0., 0., 1.)));
proto::Submap proto; const proto::Submap proto =
expected.ToProto(&proto, true /* include_probability_grid_data */); expected.ToProto(true /* include_probability_grid_data */);
EXPECT_FALSE(proto.has_submap_2d()); EXPECT_FALSE(proto.has_submap_2d());
EXPECT_TRUE(proto.has_submap_3d()); EXPECT_TRUE(proto.has_submap_3d());
const auto actual = Submap3D(proto.submap_3d()); const auto actual = Submap3D(proto.submap_3d());

View File

@ -62,8 +62,7 @@ class Submap {
: local_pose_(local_submap_pose) {} : local_pose_(local_submap_pose) {}
virtual ~Submap() {} virtual ~Submap() {}
virtual void ToProto(proto::Submap* proto, virtual proto::Submap ToProto(bool include_probability_grid_data) const = 0;
bool include_probability_grid_data) const = 0;
virtual void UpdateFromProto(const proto::Submap& proto) = 0; virtual void UpdateFromProto(const proto::Submap& proto) = 0;
// Fills data into the 'response'. // Fills data into the 'response'.