30 #include <can_msgs/Frame.h> 34 #include <gtest/gtest.h> 38 TEST(ConversionTest, socketCANToTopicStandard)
47 for (uint8_t i = 0; i < f.
dlc; ++i)
54 EXPECT_EQ(
false, m.is_error);
55 EXPECT_EQ(
false, m.is_rtr);
56 EXPECT_EQ(
false, m.is_extended);
58 for (uint8_t i=0; i < 8; i++)
60 EXPECT_EQ(i, m.data[i]);
65 TEST(ConversionTest, socketCANToTopicFlags)
72 EXPECT_EQ(
true, m.is_error);
77 EXPECT_EQ(
true, m.is_rtr);
82 EXPECT_EQ(
true, m.is_extended);
87 TEST(ConversionTest, topicToSocketCANStandard)
95 m.is_extended =
false;
96 for (uint8_t i = 0; i < m.dlc; ++i)
101 EXPECT_EQ(127, f.
id);
104 EXPECT_EQ(
false, f.
is_rtr);
108 for (uint8_t i=0; i < 8; i++)
110 EXPECT_EQ(i, f.
data[i]);
114 TEST(ConversionTest, topicToSocketCANFlags)
126 EXPECT_EQ(
true, f.
is_rtr);
129 m.is_extended =
true;
132 m.is_extended =
false;
136 int main(
int argc,
char **argv)
138 testing::InitGoogleTest(&argc, argv);
139 return RUN_ALL_TESTS();
TEST(ConversionTest, socketCANToTopicStandard)
int main(int argc, char **argv)
boost::array< value_type, 8 > data
void convertMessageToSocketCAN(const can_msgs::Frame &m, can::Frame &f)
void convertSocketCANToMessage(const can::Frame &f, can_msgs::Frame &m)