30 #include <can_msgs/Frame.h>
34 #include <gtest/gtest.h>
52 TEST(TopicToSocketCANTest, checkCorrectData)
61 to_socketcan_bridge.
setup();
64 driver_->init(
"string_not_used",
true);
67 ros::Publisher publisher_ = nh.advertise<can_msgs::Frame>(
"sent_messages", 10);
79 msg.is_extended =
true;
84 for (uint8_t i=0; i < msg.dlc; i++)
89 msg.header.frame_id =
"0";
99 can_msgs::Frame received;
103 EXPECT_EQ(received.id, msg.id);
104 EXPECT_EQ(received.dlc, msg.dlc);
105 EXPECT_EQ(received.is_extended, msg.is_extended);
106 EXPECT_EQ(received.is_rtr, msg.is_rtr);
107 EXPECT_EQ(received.is_error, msg.is_error);
108 EXPECT_EQ(received.data, msg.data);
111 TEST(TopicToSocketCANTest, checkInvalidFrameHandling)
126 to_socketcan_bridge.
setup();
129 ros::Publisher publisher_ = nh.advertise<can_msgs::Frame>(
"sent_messages", 10);
140 msg.is_extended =
false;
142 msg.header.frame_id =
"0";
151 EXPECT_EQ(frame_collector_.frames.size(), 0);
153 msg.is_extended =
true;
159 EXPECT_EQ(frame_collector_.frames.size(), 1);
162 frame_collector_.frames.clear();
170 EXPECT_EQ(frame_collector_.frames.size(), 0);
173 int main(
int argc,
char **argv)
178 testing::InitGoogleTest(&argc, argv);
179 return RUN_ALL_TESTS();