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/socketcan_to_topic.h>
00028
00029 #include <can_msgs/Frame.h>
00030 #include <socketcan_interface/socketcan.h>
00031 #include <socketcan_interface/dummy.h>
00032
00033 #include <gtest/gtest.h>
00034 #include <ros/ros.h>
00035 #include <list>
00036
00037 class msgCollector
00038 {
00039 public:
00040 std::list<can_msgs::Frame> messages;
00041
00042 msgCollector() {}
00043
00044 void msgCallback(const can_msgs::Frame& f)
00045 {
00046 messages.push_back(f);
00047 }
00048 };
00049
00050
00051 TEST(SocketCANToTopicTest, checkCorrectData)
00052 {
00053 ros::NodeHandle nh(""), nh_param("~");
00054
00055
00056 boost::shared_ptr<can::DummyInterface> driver_ = boost::make_shared<can::DummyInterface>(true);
00057
00058
00059 socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
00060 to_topic_bridge.setup();
00061
00062
00063 driver_->init("string_not_used", true);
00064
00065
00066 msgCollector message_collector_;
00067
00068
00069 ros::Subscriber subscriber_ = nh.subscribe("received_messages", 1, &msgCollector::msgCallback, &message_collector_);
00070
00071
00072 can::Frame f;
00073 f.is_extended = true;
00074 f.is_rtr = false;
00075 f.is_error = false;
00076 f.id = 0x1337;
00077 f.dlc = 8;
00078 for (uint8_t i=0; i < f.dlc; i++)
00079 {
00080 f.data[i] = i;
00081 }
00082
00083
00084 driver_->send(f);
00085
00086
00087 ros::WallDuration(1.0).sleep();
00088 ros::spinOnce();
00089
00090
00091 can_msgs::Frame received;
00092 received = message_collector_.messages.back();
00093 EXPECT_EQ(received.id, f.id);
00094 EXPECT_EQ(received.dlc, f.dlc);
00095 EXPECT_EQ(received.is_extended, f.is_extended);
00096 EXPECT_EQ(received.is_rtr, f.is_rtr);
00097 EXPECT_EQ(received.is_error, f.is_error);
00098 EXPECT_EQ(received.data, f.data);
00099 }
00100
00101 TEST(SocketCANToTopicTest, checkInvalidFrameHandling)
00102 {
00103
00104
00105
00106
00107
00108
00109
00110 ros::NodeHandle nh(""), nh_param("~");
00111
00112
00113 boost::shared_ptr<can::DummyInterface> driver_ = boost::make_shared<can::DummyInterface>(true);
00114
00115
00116 socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
00117 to_topic_bridge.setup();
00118
00119
00120 msgCollector message_collector_;
00121
00122
00123 ros::Subscriber subscriber_ = nh.subscribe("received_messages", 1, &msgCollector::msgCallback, &message_collector_);
00124
00125
00126 can::Frame f;
00127 f.is_extended = false;
00128 f.id = (1<<11)+1;
00129
00130
00131
00132
00133
00134 ros::WallDuration(1.0).sleep();
00135 ros::spinOnce();
00136 EXPECT_EQ(message_collector_.messages.size(), 0);
00137
00138 f.is_extended = true;
00139 f.id = (1<<11)+1;
00140
00141 driver_->send(f);
00142 ros::WallDuration(1.0).sleep();
00143 ros::spinOnce();
00144 EXPECT_EQ(message_collector_.messages.size(), 1);
00145 }
00146
00147 int main(int argc, char **argv)
00148 {
00149 ros::init(argc, argv, "test_to_topic");
00150 ros::WallDuration(1.0).sleep();
00151 testing::InitGoogleTest(&argc, argv);
00152 return RUN_ALL_TESTS();
00153 }