record_file_test.cc 9.5 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30
/******************************************************************************
 * Copyright 2018 The Apollo Authors. All Rights Reserved.
 *
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 * http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 *****************************************************************************/

#include <gtest/gtest.h>
#include <unistd.h>
#include <atomic>
#include <string>

#include "cyber/record/file/record_file_base.h"
#include "cyber/record/file/record_file_reader.h"
#include "cyber/record/file/record_file_writer.h"
#include "cyber/record/header_builder.h"

namespace apollo {
namespace cyber {
namespace record {

31 32 33 34 35 36
const char CHAN_1[] = "/test1";
const char CHAN_2[] = "/test2";
const char MSG_TYPE[] = "apollo.cyber.proto.Test";
const char STR_10B[] = "1234567890";
const char TEST_FILE_1[] = "test_1.record";
const char TEST_FILE_2[] = "test_2.record";
37 38

TEST(ChunkTest, TestAll) {
39 40 41 42 43 44
  Chunk* ck = new Chunk();
  ASSERT_EQ(0, ck->header_.begin_time());
  ASSERT_EQ(0, ck->header_.end_time());
  ASSERT_EQ(0, ck->header_.raw_size());
  ASSERT_EQ(0, ck->header_.message_number());
  ASSERT_TRUE(ck->empty());
45 46

  SingleMessage msg1;
47 48
  msg1.set_channel_name(CHAN_1);
  msg1.set_content(STR_10B);
49 50
  msg1.set_time(1e9);

51 52 53 54 55 56
  ck->add(msg1);
  ASSERT_EQ(1e9, ck->header_.begin_time());
  ASSERT_EQ(1e9, ck->header_.end_time());
  ASSERT_EQ(10, ck->header_.raw_size());
  ASSERT_EQ(1, ck->header_.message_number());
  ASSERT_FALSE(ck->empty());
57 58

  SingleMessage msg2;
59 60
  msg2.set_channel_name(CHAN_2);
  msg2.set_content(STR_10B);
61 62
  msg2.set_time(2e9);

63 64 65 66 67 68 69 70 71 72 73 74 75
  ck->add(msg2);
  ASSERT_EQ(1e9, ck->header_.begin_time());
  ASSERT_EQ(2e9, ck->header_.end_time());
  ASSERT_EQ(20, ck->header_.raw_size());
  ASSERT_EQ(2, ck->header_.message_number());
  ASSERT_FALSE(ck->empty());

  ck->clear();
  ASSERT_EQ(0, ck->header_.begin_time());
  ASSERT_EQ(0, ck->header_.end_time());
  ASSERT_EQ(0, ck->header_.raw_size());
  ASSERT_EQ(0, ck->header_.message_number());
  ASSERT_TRUE(ck->empty());
76 77 78 79
}

TEST(RecordFileTest, TestOneMessageFile) {
  // writer open one message file
80 81 82
  RecordFileWriter* rfw = new RecordFileWriter();
  ASSERT_TRUE(rfw->Open(TEST_FILE_1));
  ASSERT_EQ(TEST_FILE_1, rfw->GetPath());
83 84 85 86 87

  // write header section
  Header hdr1 = HeaderBuilder::GetHeaderWithSegmentParams(0, 0);
  hdr1.set_chunk_interval(0);
  hdr1.set_chunk_raw_size(0);
88 89
  ASSERT_TRUE(rfw->WriteHeader(hdr1));
  ASSERT_FALSE(rfw->GetHeader().is_complete());
90 91 92

  // write channel section
  Channel chan1;
93 94 95 96
  chan1.set_name(CHAN_1);
  chan1.set_message_type(MSG_TYPE);
  chan1.set_proto_desc(STR_10B);
  ASSERT_TRUE(rfw->WriteChannel(chan1));
97 98 99 100

  // write chunk section
  SingleMessage msg1;
  msg1.set_channel_name(chan1.name());
101
  msg1.set_content(STR_10B);
102
  msg1.set_time(1e9);
103 104
  ASSERT_TRUE(rfw->WriteMessage(msg1));
  ASSERT_EQ(1, rfw->GetMessageNumber(chan1.name()));
105 106

  // writer close one message file
107 108 109 110 111 112 113 114
  rfw->Close();
  ASSERT_TRUE(rfw->GetHeader().is_complete());
  ASSERT_EQ(1, rfw->GetHeader().chunk_number());
  ASSERT_EQ(1e9, rfw->GetHeader().begin_time());
  ASSERT_EQ(1e9, rfw->GetHeader().end_time());
  ASSERT_EQ(1, rfw->GetHeader().message_number());
  hdr1 = rfw->GetHeader();
  delete rfw;
115 116

  // header open one message file
117 118 119
  RecordFileReader* rfr = new RecordFileReader();
  ASSERT_TRUE(rfr->Open(TEST_FILE_1));
  ASSERT_EQ(TEST_FILE_1, rfr->GetPath());
120 121 122 123

  Section sec;

  // read header section
124
  Header hdr2 = rfr->GetHeader();
125 126 127 128 129 130
  ASSERT_EQ(hdr2.chunk_number(), hdr1.chunk_number());
  ASSERT_EQ(hdr2.begin_time(), hdr1.begin_time());
  ASSERT_EQ(hdr2.end_time(), hdr1.end_time());
  ASSERT_EQ(hdr2.message_number(), hdr1.message_number());

  // read channel section
131
  ASSERT_TRUE(rfr->ReadSection(&sec));
132 133
  ASSERT_EQ(SectionType::SECTION_CHANNEL, sec.type);
  Channel chan2;
134
  ASSERT_TRUE(rfr->ReadSection<Channel>(sec.size, &chan2));
135 136 137 138 139
  ASSERT_EQ(chan2.name(), chan1.name());
  ASSERT_EQ(chan2.message_type(), chan1.message_type());
  ASSERT_EQ(chan2.proto_desc(), chan1.proto_desc());

  // read chunk header section
140
  ASSERT_TRUE(rfr->ReadSection(&sec));
141 142
  ASSERT_EQ(SectionType::SECTION_CHUNK_HEADER, sec.type);
  ChunkHeader ckh2;
143
  ASSERT_TRUE(rfr->ReadSection<ChunkHeader>(sec.size, &ckh2));
144 145 146 147 148 149
  ASSERT_EQ(ckh2.begin_time(), 1e9);
  ASSERT_EQ(ckh2.end_time(), 1e9);
  ASSERT_EQ(ckh2.raw_size(), 10);
  ASSERT_EQ(ckh2.message_number(), 1);

  // read chunk body section
150
  ASSERT_TRUE(rfr->ReadSection(&sec));
151 152
  ASSERT_EQ(SectionType::SECTION_CHUNK_BODY, sec.type);
  ChunkBody ckb2;
153
  ASSERT_TRUE(rfr->ReadSection<ChunkBody>(sec.size, &ckb2));
154 155 156 157 158
  ASSERT_EQ(ckb2.messages_size(), 1);
  ASSERT_EQ(ckb2.messages(0).channel_name(), ckb2.messages(0).channel_name());
  ASSERT_EQ(ckb2.messages(0).time(), ckb2.messages(0).time());
  ASSERT_EQ(ckb2.messages(0).content(), ckb2.messages(0).content());

159 160
  // close recorder file reader
  delete rfr;
161 162 163
}

TEST(RecordFileTest, TestOneChunkFile) {
164
  RecordFileWriter* rfw = new RecordFileWriter();
165

166 167
  ASSERT_TRUE(rfw->Open(TEST_FILE_1));
  ASSERT_EQ(TEST_FILE_1, rfw->GetPath());
168 169 170 171

  Header header = HeaderBuilder::GetHeaderWithChunkParams(0, 0);
  header.set_segment_interval(0);
  header.set_segment_raw_size(0);
172 173
  ASSERT_TRUE(rfw->WriteHeader(header));
  ASSERT_FALSE(rfw->GetHeader().is_complete());
174 175

  Channel chan1;
176 177 178 179
  chan1.set_name(CHAN_1);
  chan1.set_message_type(MSG_TYPE);
  chan1.set_proto_desc(STR_10B);
  ASSERT_TRUE(rfw->WriteChannel(chan1));
180 181

  Channel chan2;
182 183 184 185
  chan2.set_name(CHAN_2);
  chan2.set_message_type(MSG_TYPE);
  chan2.set_proto_desc(STR_10B);
  ASSERT_TRUE(rfw->WriteChannel(chan2));
186 187 188

  SingleMessage msg1;
  msg1.set_channel_name(chan1.name());
189
  msg1.set_content(STR_10B);
190
  msg1.set_time(1e9);
191 192
  ASSERT_TRUE(rfw->WriteMessage(msg1));
  ASSERT_EQ(1, rfw->GetMessageNumber(chan1.name()));
193 194 195

  SingleMessage msg2;
  msg2.set_channel_name(chan2.name());
196
  msg2.set_content(STR_10B);
197
  msg2.set_time(2e9);
198 199
  ASSERT_TRUE(rfw->WriteMessage(msg2));
  ASSERT_EQ(1, rfw->GetMessageNumber(chan2.name()));
200 201 202

  SingleMessage msg3;
  msg3.set_channel_name(chan1.name());
203
  msg3.set_content(STR_10B);
204
  msg3.set_time(3e9);
205 206 207 208 209 210 211 212 213
  ASSERT_TRUE(rfw->WriteMessage(msg3));
  ASSERT_EQ(2, rfw->GetMessageNumber(chan1.name()));

  rfw->Close();
  ASSERT_TRUE(rfw->GetHeader().is_complete());
  ASSERT_EQ(1, rfw->GetHeader().chunk_number());
  ASSERT_EQ(1e9, rfw->GetHeader().begin_time());
  ASSERT_EQ(3e9, rfw->GetHeader().end_time());
  ASSERT_EQ(3, rfw->GetHeader().message_number());
214 215
}

fengqikai1414's avatar
fengqikai1414 已提交
216 217 218 219
TEST(RecordFileTest, TestIndex) {
  {
    RecordFileWriter* rfw = new RecordFileWriter();

220 221
    ASSERT_TRUE(rfw->Open(TEST_FILE_2));
    ASSERT_EQ(TEST_FILE_2, rfw->GetPath());
fengqikai1414's avatar
fengqikai1414 已提交
222 223 224 225 226 227 228 229

    Header header = HeaderBuilder::GetHeaderWithChunkParams(0, 0);
    header.set_segment_interval(0);
    header.set_segment_raw_size(0);
    ASSERT_TRUE(rfw->WriteHeader(header));
    ASSERT_FALSE(rfw->GetHeader().is_complete());

    Channel chan1;
230 231 232
    chan1.set_name(CHAN_1);
    chan1.set_message_type(MSG_TYPE);
    chan1.set_proto_desc(STR_10B);
fengqikai1414's avatar
fengqikai1414 已提交
233 234 235
    ASSERT_TRUE(rfw->WriteChannel(chan1));

    Channel chan2;
236 237 238
    chan2.set_name(CHAN_2);
    chan2.set_message_type(MSG_TYPE);
    chan2.set_proto_desc(STR_10B);
fengqikai1414's avatar
fengqikai1414 已提交
239 240 241 242
    ASSERT_TRUE(rfw->WriteChannel(chan2));

    SingleMessage msg1;
    msg1.set_channel_name(chan1.name());
243
    msg1.set_content(STR_10B);
fengqikai1414's avatar
fengqikai1414 已提交
244 245 246 247 248 249
    msg1.set_time(1e9);
    ASSERT_TRUE(rfw->WriteMessage(msg1));
    ASSERT_EQ(1, rfw->GetMessageNumber(chan1.name()));

    SingleMessage msg2;
    msg2.set_channel_name(chan2.name());
250
    msg2.set_content(STR_10B);
fengqikai1414's avatar
fengqikai1414 已提交
251 252 253 254 255 256
    msg2.set_time(2e9);
    ASSERT_TRUE(rfw->WriteMessage(msg2));
    ASSERT_EQ(1, rfw->GetMessageNumber(chan2.name()));

    SingleMessage msg3;
    msg3.set_channel_name(chan1.name());
257
    msg3.set_content(STR_10B);
fengqikai1414's avatar
fengqikai1414 已提交
258 259 260 261 262 263 264 265 266 267 268 269 270
    msg3.set_time(3e9);
    ASSERT_TRUE(rfw->WriteMessage(msg3));
    ASSERT_EQ(2, rfw->GetMessageNumber(chan1.name()));

    rfw->Close();
    ASSERT_TRUE(rfw->GetHeader().is_complete());
    ASSERT_EQ(1, rfw->GetHeader().chunk_number());
    ASSERT_EQ(1e9, rfw->GetHeader().begin_time());
    ASSERT_EQ(3e9, rfw->GetHeader().end_time());
    ASSERT_EQ(3, rfw->GetHeader().message_number());
  }
  {
    RecordFileReader reader;
271
    reader.Open(TEST_FILE_2);
fengqikai1414's avatar
fengqikai1414 已提交
272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301

    reader.ReadIndex();
    const auto& index = reader.GetIndex();

    // Walk through file the long way and check that the indexes match the
    // sections
    reader.Reset();
    Section section;
    for (uint64_t pos = reader.CurrentPosition();
         reader.ReadSection(&section) && reader.SkipSection(section.size);
         pos = reader.CurrentPosition()) {
      // Find index at position
      if (section.type != SectionType::SECTION_INDEX) {
        bool found = false;
        SingleIndex match;
        for (const auto& row : index.indexes()) {
          if (row.position() == pos) {
            match = row;
            found = true;
            break;
          }
        }
        ASSERT_TRUE(found);
        EXPECT_EQ(match.position(), pos);
        EXPECT_EQ(match.type(), section.type);
      }
    }
  }
}

302 303 304 305 306 307 308 309 310
}  // namespace record
}  // namespace cyber
}  // namespace apollo

int main(int argc, char** argv) {
  testing::GTEST_FLAG(catch_exceptions) = 1;
  testing::InitGoogleTest(&argc, argv);
  google::InitGoogleLogging(argv[0]);
  FLAGS_logtostderr = true;
311
  return RUN_ALL_TESTS();
312
}