Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/io/internal/pbstream_info.h"
00018
00019 #include <map>
00020 #include <sstream>
00021 #include <string>
00022
00023 #include "cartographer/io/proto_stream.h"
00024 #include "cartographer/io/proto_stream_deserializer.h"
00025 #include "gflags/gflags.h"
00026 #include "glog/logging.h"
00027
00028 DEFINE_bool(all_debug_strings, false,
00029 "Print debug strings of all serialized data.");
00030
00031 using cartographer::mapping::proto::SerializedData;
00032
00033 namespace cartographer {
00034 namespace io {
00035 namespace {
00036
00037 void Run(const std::string& pbstream_filename, bool all_debug_strings) {
00038 LOG(INFO) << "Reading pbstream file from '" << pbstream_filename << "'...";
00039 io::ProtoStreamReader reader(pbstream_filename);
00040 io::ProtoStreamDeserializer deserializer(&reader);
00041 const auto header = deserializer.header();
00042 LOG(INFO) << "Header: " << header.DebugString();
00043 for (const mapping::proto::TrajectoryBuilderOptionsWithSensorIds&
00044 trajectory_options : deserializer.all_trajectory_builder_options()
00045 .options_with_sensor_ids()) {
00046 LOG(INFO) << "Trajectory options: " << trajectory_options.DebugString();
00047 }
00048 const mapping::proto::PoseGraph pose_graph = deserializer.pose_graph();
00049 for (const mapping::proto::Trajectory& trajectory : pose_graph.trajectory()) {
00050 LOG(INFO) << "Trajectory id: " << trajectory.trajectory_id()
00051 << " has #nodes " << trajectory.node_size() << " has #submaps "
00052 << trajectory.submap_size();
00053 }
00054 if (all_debug_strings) {
00055 LOG(INFO) << "Pose graph: " << pose_graph.DebugString();
00056 }
00057
00058 const std::map<SerializedData::DataCase, std::string> data_case_to_name = {
00059 {SerializedData::kSubmap, "submap"},
00060 {SerializedData::kNode, "node"},
00061 {SerializedData::kTrajectoryData, "trajectory_data"},
00062 {SerializedData::kImuData, "imu_data"},
00063 {SerializedData::kOdometryData, "odometry_data"},
00064 {SerializedData::kFixedFramePoseData, "fixed_frame_pose_data"},
00065 {SerializedData::kLandmarkData, "landmark_data"},
00066 };
00067
00068 std::map<std::string, int> data_counts = {
00069 {"submap_2d", 0},
00070 {"submap_2d_grid", 0},
00071 {"submap_3d", 0},
00072 {"submap_3d_high_resolution_hybrid_grid", 0},
00073 };
00074 SerializedData proto;
00075 while (deserializer.ReadNextSerializedData(&proto)) {
00076 if (all_debug_strings) {
00077 LOG(INFO) << "Serialized data: " << proto.DebugString();
00078 }
00079 auto it = data_case_to_name.find(proto.data_case());
00080 if (it == data_case_to_name.end()) {
00081 LOG(WARNING) << "Skipping unknown message type in stream: "
00082 << proto.GetTypeName();
00083 }
00084 const std::string& data_name = it->second;
00085 ++data_counts[data_name];
00086 if (proto.data_case() == SerializedData::kSubmap) {
00087 if (proto.mutable_submap()->has_submap_2d()) {
00088 ++data_counts["submap_2d"];
00089 if (proto.mutable_submap()->mutable_submap_2d()->has_grid()) {
00090 ++data_counts["submap_2d_grid"];
00091 }
00092 }
00093 if (proto.mutable_submap()->has_submap_3d()) {
00094 ++data_counts["submap_3d"];
00095 if (proto.mutable_submap()
00096 ->mutable_submap_3d()
00097 ->has_high_resolution_hybrid_grid()) {
00098 ++data_counts["submap_3d_high_resolution_hybrid_grid"];
00099 }
00100 }
00101 }
00102 }
00103
00104 for (const auto& entry : data_counts) {
00105 LOG(INFO) << "SerializedData package contains #" << entry.first << ": "
00106 << entry.second;
00107 }
00108 }
00109 }
00110
00111 int pbstream_info(int argc, char* argv[]) {
00112 std::stringstream ss;
00113 ss << "\n\n"
00114 << "Reads a pbstream file and summarizes its contents.\n\n"
00115 << "Usage: " << argv[0] << " " << argv[1]
00116 << " <pbstream_filename> [flags]\n";
00117 google::SetUsageMessage(ss.str());
00118 if (argc < 3) {
00119 google::ShowUsageWithFlagsRestrict(argv[0], "pbstream_info");
00120 return EXIT_FAILURE;
00121 }
00122 Run(argv[2], FLAGS_all_debug_strings);
00123 return EXIT_SUCCESS;
00124 }
00125
00126 }
00127 }