Add ProtoStreamWriterInterface and implement forwarding writer. (#849)
parent
65889f14a0
commit
edb18231b6
|
@ -16,9 +16,18 @@
|
||||||
|
|
||||||
#include "cartographer/io/in_memory_proto_stream.h"
|
#include "cartographer/io/in_memory_proto_stream.h"
|
||||||
|
|
||||||
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer {
|
namespace cartographer {
|
||||||
namespace io {
|
namespace io {
|
||||||
|
|
||||||
|
void ForwardingProtoStreamWriter::WriteProto(
|
||||||
|
const google::protobuf::Message& proto) {
|
||||||
|
CHECK(writer_callback_(&proto));
|
||||||
|
}
|
||||||
|
|
||||||
|
bool ForwardingProtoStreamWriter::Close() { return writer_callback_(nullptr); }
|
||||||
|
|
||||||
bool InMemoryProtoStreamReader::ReadProto(google::protobuf::Message* proto) {
|
bool InMemoryProtoStreamReader::ReadProto(google::protobuf::Message* proto) {
|
||||||
if (eof()) return false;
|
if (eof()) return false;
|
||||||
proto->CopyFrom(*map_chunks_.front());
|
proto->CopyFrom(*map_chunks_.front());
|
||||||
|
|
|
@ -27,6 +27,26 @@
|
||||||
namespace cartographer {
|
namespace cartographer {
|
||||||
namespace io {
|
namespace io {
|
||||||
|
|
||||||
|
class ForwardingProtoStreamWriter
|
||||||
|
: public cartographer::io::ProtoStreamWriterInterface {
|
||||||
|
public:
|
||||||
|
// A callback that is invoked anytime 'WriteProto()' is called on the
|
||||||
|
// 'ForwardingProtoStreamWriter'. When 'Close()' is called on the
|
||||||
|
// 'ForwardingProtoStreamWriter' the callback is invoked with a 'nullptr'.
|
||||||
|
using WriterCallback =
|
||||||
|
std::function<bool(const google::protobuf::Message* proto)>;
|
||||||
|
|
||||||
|
explicit ForwardingProtoStreamWriter(WriterCallback writer_callback)
|
||||||
|
: writer_callback_(writer_callback) {}
|
||||||
|
~ForwardingProtoStreamWriter() = default;
|
||||||
|
|
||||||
|
void WriteProto(const google::protobuf::Message& proto) override;
|
||||||
|
bool Close() override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
WriterCallback writer_callback_;
|
||||||
|
};
|
||||||
|
|
||||||
class InMemoryProtoStreamReader
|
class InMemoryProtoStreamReader
|
||||||
: public cartographer::io::ProtoStreamReaderInterface {
|
: public cartographer::io::ProtoStreamReaderInterface {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -32,7 +32,7 @@ namespace io {
|
||||||
//
|
//
|
||||||
// TODO(whess): Compress the file instead of individual messages for better
|
// TODO(whess): Compress the file instead of individual messages for better
|
||||||
// compression performance? Should we use LZ4?
|
// compression performance? Should we use LZ4?
|
||||||
class ProtoStreamWriter {
|
class ProtoStreamWriter : public ProtoStreamWriterInterface {
|
||||||
public:
|
public:
|
||||||
ProtoStreamWriter(const std::string& filename);
|
ProtoStreamWriter(const std::string& filename);
|
||||||
~ProtoStreamWriter() = default;
|
~ProtoStreamWriter() = default;
|
||||||
|
@ -40,11 +40,8 @@ class ProtoStreamWriter {
|
||||||
ProtoStreamWriter(const ProtoStreamWriter&) = delete;
|
ProtoStreamWriter(const ProtoStreamWriter&) = delete;
|
||||||
ProtoStreamWriter& operator=(const ProtoStreamWriter&) = delete;
|
ProtoStreamWriter& operator=(const ProtoStreamWriter&) = delete;
|
||||||
|
|
||||||
// Serializes, compressed and writes the 'proto' to the file.
|
void WriteProto(const google::protobuf::Message& proto) override;
|
||||||
void WriteProto(const google::protobuf::Message& proto);
|
bool Close() override;
|
||||||
|
|
||||||
// This should be called to check whether writing was successful.
|
|
||||||
bool Close();
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void Write(const std::string& uncompressed_data);
|
void Write(const std::string& uncompressed_data);
|
||||||
|
|
|
@ -23,6 +23,18 @@
|
||||||
namespace cartographer {
|
namespace cartographer {
|
||||||
namespace io {
|
namespace io {
|
||||||
|
|
||||||
|
// A writer for writing proto messages to a pbstream.
|
||||||
|
class ProtoStreamWriterInterface {
|
||||||
|
public:
|
||||||
|
virtual ~ProtoStreamWriterInterface(){};
|
||||||
|
|
||||||
|
// Serializes, compressed and writes the 'proto' to the file.
|
||||||
|
virtual void WriteProto(const google::protobuf::Message& proto) = 0;
|
||||||
|
|
||||||
|
// This should be called to check whether writing was successful.
|
||||||
|
virtual bool Close() = 0;
|
||||||
|
};
|
||||||
|
|
||||||
// A reader of the format produced by ProtoStreamWriter.
|
// A reader of the format produced by ProtoStreamWriter.
|
||||||
class ProtoStreamReaderInterface {
|
class ProtoStreamReaderInterface {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -168,7 +168,7 @@ std::string MapBuilder::SubmapToProto(
|
||||||
return "";
|
return "";
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilder::SerializeState(io::ProtoStreamWriter* const writer) {
|
void MapBuilder::SerializeState(io::ProtoStreamWriterInterface* const writer) {
|
||||||
// We serialize the pose graph followed by all the data referenced in it.
|
// We serialize the pose graph followed by all the data referenced in it.
|
||||||
writer->WriteProto(pose_graph_->ToProto());
|
writer->WriteProto(pose_graph_->ToProto());
|
||||||
// Next we serialize all submap data.
|
// Next we serialize all submap data.
|
||||||
|
|
|
@ -60,7 +60,7 @@ class MapBuilder : public MapBuilderInterface {
|
||||||
std::string SubmapToProto(const SubmapId& submap_id,
|
std::string SubmapToProto(const SubmapId& submap_id,
|
||||||
proto::SubmapQuery::Response* response) override;
|
proto::SubmapQuery::Response* response) override;
|
||||||
|
|
||||||
void SerializeState(io::ProtoStreamWriter* writer) override;
|
void SerializeState(io::ProtoStreamWriterInterface* writer) override;
|
||||||
|
|
||||||
void LoadMap(io::ProtoStreamReaderInterface* reader) override;
|
void LoadMap(io::ProtoStreamReaderInterface* reader) override;
|
||||||
|
|
||||||
|
|
|
@ -74,7 +74,7 @@ class MapBuilderInterface {
|
||||||
proto::SubmapQuery::Response* response) = 0;
|
proto::SubmapQuery::Response* response) = 0;
|
||||||
|
|
||||||
// Serializes the current state to a proto stream.
|
// Serializes the current state to a proto stream.
|
||||||
virtual void SerializeState(io::ProtoStreamWriter* writer) = 0;
|
virtual void SerializeState(io::ProtoStreamWriterInterface* writer) = 0;
|
||||||
|
|
||||||
// Loads submaps from a proto stream into a new frozen trajectory.
|
// Loads submaps from a proto stream into a new frozen trajectory.
|
||||||
virtual void LoadMap(io::ProtoStreamReaderInterface* reader) = 0;
|
virtual void LoadMap(io::ProtoStreamReaderInterface* reader) = 0;
|
||||||
|
|
|
@ -56,7 +56,8 @@ class MockMapBuilder : public cartographer::mapping::MapBuilderInterface {
|
||||||
SubmapToProto,
|
SubmapToProto,
|
||||||
std::string(const cartographer::mapping::SubmapId&,
|
std::string(const cartographer::mapping::SubmapId&,
|
||||||
cartographer::mapping::proto::SubmapQuery::Response*));
|
cartographer::mapping::proto::SubmapQuery::Response*));
|
||||||
MOCK_METHOD1(SerializeState, void(cartographer::io::ProtoStreamWriter*));
|
MOCK_METHOD1(SerializeState,
|
||||||
|
void(cartographer::io::ProtoStreamWriterInterface*));
|
||||||
MOCK_METHOD1(LoadMap, void(cartographer::io::ProtoStreamReaderInterface*));
|
MOCK_METHOD1(LoadMap, void(cartographer::io::ProtoStreamReaderInterface*));
|
||||||
MOCK_CONST_METHOD0(num_trajectory_builders, int());
|
MOCK_CONST_METHOD0(num_trajectory_builders, int());
|
||||||
MOCK_METHOD0(pose_graph, PoseGraphInterface*());
|
MOCK_METHOD0(pose_graph, PoseGraphInterface*());
|
||||||
|
|
|
@ -88,7 +88,7 @@ std::string MapBuilderStub::SubmapToProto(
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilderStub::SerializeState(
|
void MapBuilderStub::SerializeState(
|
||||||
cartographer::io::ProtoStreamWriter* writer) {
|
cartographer::io::ProtoStreamWriterInterface* writer) {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -47,7 +47,8 @@ class MapBuilderStub : public cartographer::mapping::MapBuilderInterface {
|
||||||
std::string SubmapToProto(
|
std::string SubmapToProto(
|
||||||
const cartographer::mapping::SubmapId& submap_id,
|
const cartographer::mapping::SubmapId& submap_id,
|
||||||
cartographer::mapping::proto::SubmapQuery::Response* response) override;
|
cartographer::mapping::proto::SubmapQuery::Response* response) override;
|
||||||
void SerializeState(cartographer::io::ProtoStreamWriter* writer) override;
|
void SerializeState(
|
||||||
|
cartographer::io::ProtoStreamWriterInterface* writer) override;
|
||||||
void LoadMap(cartographer::io::ProtoStreamReaderInterface* reader) override;
|
void LoadMap(cartographer::io::ProtoStreamReaderInterface* reader) override;
|
||||||
int num_trajectory_builders() const override;
|
int num_trajectory_builders() const override;
|
||||||
cartographer::mapping::PoseGraphInterface* pose_graph() override;
|
cartographer::mapping::PoseGraphInterface* pose_graph() override;
|
||||||
|
|
Loading…
Reference in New Issue