29 #include <can_msgs/Frame.h>
34 #include <gtest/gtest.h>
61 TEST(SocketCANToTopicTest, checkCorrectData)
70 to_topic_bridge.
setup();
73 driver_->init(
"string_not_used",
true);
88 for (uint8_t i=0; i <
f.dlc; i++)
100 ASSERT_EQ(1, message_collector_.
messages.size());
104 can_msgs::Frame msg = message_collector_.
messages.back();
107 EXPECT_EQ(received.
id,
f.id);
108 EXPECT_EQ(received.
dlc,
f.dlc);
110 EXPECT_EQ(received.
is_rtr,
f.is_rtr);
111 EXPECT_EQ(received.
is_error,
f.is_error);
112 EXPECT_EQ(received.
data,
f.data);
115 TEST(SocketCANToTopicTest, checkInvalidFrameHandling)
131 to_topic_bridge.
setup();
141 f.is_extended =
false;
150 EXPECT_EQ(message_collector_.
messages.size(), 0);
152 f.is_extended =
true;
158 EXPECT_EQ(message_collector_.
messages.size(), 1);
161 TEST(SocketCANToTopicTest, checkCorrectCanIdFilter)
169 std::vector<unsigned int> pass_can_ids;
170 pass_can_ids.push_back(0x1337);
177 driver_->init(
"string_not_used",
true);
187 f.is_extended =
true;
192 for (uint8_t i=0; i <
f.dlc; i++)
204 ASSERT_EQ(1, message_collector_.
messages.size());
208 can_msgs::Frame msg = message_collector_.
messages.back();
211 EXPECT_EQ(received.
id,
f.id);
212 EXPECT_EQ(received.
dlc,
f.dlc);
214 EXPECT_EQ(received.
is_rtr,
f.is_rtr);
215 EXPECT_EQ(received.
is_error,
f.is_error);
216 EXPECT_EQ(received.
data,
f.data);
219 TEST(SocketCANToTopicTest, checkInvalidCanIdFilter)
227 std::vector<unsigned int> pass_can_ids;
228 pass_can_ids.push_back(0x300);
235 driver_->init(
"string_not_used",
true);
245 f.is_extended =
true;
250 for (uint8_t i=0; i <
f.dlc; i++)
262 EXPECT_EQ(0, message_collector_.
messages.size());
265 TEST(SocketCANToTopicTest, checkMaskFilter)
278 to_topic_bridge.
setup(filters);
281 driver_->init(
"string_not_used",
true);
289 const std::string pass1(
"300#1234"), nopass1(
"302#9999"), pass2(
"301#5678");
301 ASSERT_EQ(2, message_collector_.
messages.size());
306 int main(
int argc,
char **argv)
311 testing::InitGoogleTest(&argc, argv);
312 return RUN_ALL_TESTS();