forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathdrake_lcm_log_test.cc
58 lines (47 loc) · 1.66 KB
/
drake_lcm_log_test.cc
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
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
#include "drake/lcm/drake_lcm_log.h"
#include <memory>
#include <utility>
#include <gtest/gtest.h>
#include "drake/lcmt_drake_signal.hpp"
namespace drake {
namespace lcm {
namespace {
// Generates a log file using the write-only interface, then plays it back
// and check message content with a subscriber.
GTEST_TEST(LcmLogTest, LcmLogTestSaveAndRead) {
auto w_log = std::make_unique<DrakeLcmLog>("test.log", true);
const std::string channel_name("test_channel");
drake::lcmt_drake_signal msg{};
msg.dim = 1;
msg.val.push_back(0.1);
msg.coord.push_back("test");
msg.timestamp = 1234;
const double log_time = 111;
Publish(w_log.get(), channel_name, msg, log_time);
// Finish writing.
w_log.reset();
auto r_log = std::make_unique<DrakeLcmLog>("test.log", false);
// Add multiple subscribers to the same channel.
std::vector<drake::lcmt_drake_signal> messages(3, drake::lcmt_drake_signal{});
for (int i = 0; i < 3; i++) {
Subscribe<drake::lcmt_drake_signal>(
r_log.get(), channel_name, [i, &messages](const auto& message) {
messages[i] = message;
});
}
double r_time = r_log->GetNextMessageTime();
EXPECT_NEAR(r_time, log_time, 1e-12);
r_log->DispatchMessageAndAdvanceLog(r_time);
for (int i = 0; i < 3; i++) {
const auto& decoded_msg = messages[i];
EXPECT_EQ(msg.dim, decoded_msg.dim);
EXPECT_EQ(msg.val.size(), decoded_msg.val.size());
EXPECT_EQ(msg.val[0], decoded_msg.val[0]);
EXPECT_EQ(msg.coord.size(), decoded_msg.coord.size());
EXPECT_EQ(msg.coord[0], decoded_msg.coord[0]);
EXPECT_EQ(msg.timestamp, decoded_msg.timestamp);
}
}
} // namespace
} // namespace lcm
} // namespace drake