Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #include <socketcan_bridge/topic_to_socketcan.h>
00028 #include <socketcan_bridge/socketcan_to_topic.h>
00029
00030 #include <can_msgs/Frame.h>
00031 #include <socketcan_interface/socketcan.h>
00032
00033
00034 #include <gtest/gtest.h>
00035
00036
00037
00038 TEST(ConversionTest, socketCANToTopicStandard)
00039 {
00040 can::Frame f;
00041 can_msgs::Frame m;
00042 f.id = 127;
00043 f.dlc = 8;
00044 f.is_error = false;
00045 f.is_rtr = false;
00046 f.is_extended = false;
00047 for (uint8_t i = 0; i < f.dlc; ++i)
00048 {
00049 f.data[i] = i;
00050 }
00051 socketcan_bridge::convertSocketCANToMessage(f, m);
00052 EXPECT_EQ(127, m.id);
00053 EXPECT_EQ(8, m.dlc);
00054 EXPECT_EQ(false, m.is_error);
00055 EXPECT_EQ(false, m.is_rtr);
00056 EXPECT_EQ(false, m.is_extended);
00057
00058 for (uint8_t i=0; i < 8; i++)
00059 {
00060 EXPECT_EQ(i, m.data[i]);
00061 }
00062 }
00063
00064
00065 TEST(ConversionTest, socketCANToTopicFlags)
00066 {
00067 can::Frame f;
00068 can_msgs::Frame m;
00069
00070 f.is_error = true;
00071 socketcan_bridge::convertSocketCANToMessage(f, m);
00072 EXPECT_EQ(true, m.is_error);
00073 f.is_error = false;
00074
00075 f.is_rtr = true;
00076 socketcan_bridge::convertSocketCANToMessage(f, m);
00077 EXPECT_EQ(true, m.is_rtr);
00078 f.is_rtr = false;
00079
00080 f.is_extended = true;
00081 socketcan_bridge::convertSocketCANToMessage(f, m);
00082 EXPECT_EQ(true, m.is_extended);
00083 f.is_extended = false;
00084 }
00085
00086
00087 TEST(ConversionTest, topicToSocketCANStandard)
00088 {
00089 can::Frame f;
00090 can_msgs::Frame m;
00091 m.id = 127;
00092 m.dlc = 8;
00093 m.is_error = false;
00094 m.is_rtr = false;
00095 m.is_extended = false;
00096 for (uint8_t i = 0; i < m.dlc; ++i)
00097 {
00098 m.data[i] = i;
00099 }
00100 socketcan_bridge::convertMessageToSocketCAN(m, f);
00101 EXPECT_EQ(127, f.id);
00102 EXPECT_EQ(8, f.dlc);
00103 EXPECT_EQ(false, f.is_error);
00104 EXPECT_EQ(false, f.is_rtr);
00105 EXPECT_EQ(false, f.is_extended);
00106
00107
00108 for (uint8_t i=0; i < 8; i++)
00109 {
00110 EXPECT_EQ(i, f.data[i]);
00111 }
00112 }
00113
00114 TEST(ConversionTest, topicToSocketCANFlags)
00115 {
00116 can::Frame f;
00117 can_msgs::Frame m;
00118
00119 m.is_error = true;
00120 socketcan_bridge::convertMessageToSocketCAN(m, f);
00121 EXPECT_EQ(true, f.is_error);
00122 m.is_error = false;
00123
00124 m.is_rtr = true;
00125 socketcan_bridge::convertMessageToSocketCAN(m, f);
00126 EXPECT_EQ(true, f.is_rtr);
00127 m.is_rtr = false;
00128
00129 m.is_extended = true;
00130 socketcan_bridge::convertMessageToSocketCAN(m, f);
00131 EXPECT_EQ(true, f.is_extended);
00132 m.is_extended = false;
00133 }
00134
00135
00136 int main(int argc, char **argv)
00137 {
00138 testing::InitGoogleTest(&argc, argv);
00139 return RUN_ALL_TESTS();
00140 }