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
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 frameCollector
00038 {
00039 public:
00040 std::list<can::Frame> frames;
00041
00042 frameCollector() {}
00043
00044 void frameCallback(const can::Frame& f)
00045 {
00046 frames.push_back(f);
00047 }
00048 };
00049
00050 TEST(TopicToSocketCANTest, checkCorrectData)
00051 {
00052 ros::NodeHandle nh(""), nh_param("~");
00053
00054
00055 boost::shared_ptr<can::DummyInterface> driver_ = boost::make_shared<can::DummyInterface>(true);
00056
00057
00058 socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver_);
00059 to_socketcan_bridge.setup();
00060
00061
00062 driver_->init("string_not_used", true);
00063
00064
00065 ros::Publisher publisher_ = nh.advertise<can_msgs::Frame>("sent_messages", 10);
00066
00067
00068 frameCollector frame_collector_;
00069
00070
00071 can::CommInterface::FrameListener::Ptr frame_listener_ = driver_->createMsgListener(
00072 can::CommInterface::FrameDelegate(&frame_collector_, &frameCollector::frameCallback));
00073
00074
00075 can_msgs::Frame msg;
00076 msg.is_extended = true;
00077 msg.is_rtr = false;
00078 msg.is_error = false;
00079 msg.id = 0x1337;
00080 msg.dlc = 8;
00081 for (uint8_t i=0; i < msg.dlc; i++)
00082 {
00083 msg.data[i] = i;
00084 }
00085
00086 msg.header.frame_id = "0";
00087 msg.header.stamp = ros::Time::now();
00088
00089
00090 publisher_.publish(msg);
00091
00092
00093 ros::WallDuration(1.0).sleep();
00094 ros::spinOnce();
00095
00096 can::Frame received;
00097 received = frame_collector_.frames.back();
00098 EXPECT_EQ(received.id, msg.id);
00099 EXPECT_EQ(received.dlc, msg.dlc);
00100 EXPECT_EQ(received.is_extended, msg.is_extended);
00101 EXPECT_EQ(received.is_rtr, msg.is_rtr);
00102 EXPECT_EQ(received.is_error, msg.is_error);
00103 EXPECT_EQ(received.data, msg.data);
00104 }
00105
00106 TEST(TopicToSocketCANTest, checkInvalidFrameHandling)
00107 {
00108
00109
00110
00111
00112
00113
00114 ros::NodeHandle nh(""), nh_param("~");
00115
00116
00117 boost::shared_ptr<can::DummyInterface> driver_ = boost::make_shared<can::DummyInterface>(true);
00118
00119
00120 socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver_);
00121 to_socketcan_bridge.setup();
00122
00123
00124 ros::Publisher publisher_ = nh.advertise<can_msgs::Frame>("sent_messages", 10);
00125
00126
00127 frameCollector frame_collector_;
00128
00129
00130 can::CommInterface::FrameListener::Ptr frame_listener_ = driver_->createMsgListener(
00131 can::CommInterface::FrameDelegate(&frame_collector_, &frameCollector::frameCallback));
00132
00133
00134 can_msgs::Frame msg;
00135 msg.is_extended = false;
00136 msg.id = (1<<11)+1;
00137 msg.header.frame_id = "0";
00138 msg.header.stamp = ros::Time::now();
00139
00140
00141 publisher_.publish(msg);
00142
00143
00144 ros::WallDuration(1.0).sleep();
00145 ros::spinOnce();
00146 EXPECT_EQ(frame_collector_.frames.size(), 0);
00147
00148 msg.is_extended = true;
00149 msg.id = (1<<11)+1;
00150
00151 publisher_.publish(msg);
00152 ros::WallDuration(1.0).sleep();
00153 ros::spinOnce();
00154 EXPECT_EQ(frame_collector_.frames.size(), 1);
00155
00156
00157 frame_collector_.frames.clear();
00158
00159
00160
00161 msg.dlc = 10;
00162 publisher_.publish(msg);
00163 ros::WallDuration(1.0).sleep();
00164 ros::spinOnce();
00165 EXPECT_EQ(frame_collector_.frames.size(), 0);
00166 }
00167
00168 int main(int argc, char **argv)
00169 {
00170 ros::init(argc, argv, "test_to_topic");
00171 ros::WallDuration(1.0).sleep();
00172 testing::InitGoogleTest(&argc, argv);
00173 return RUN_ALL_TESTS();
00174 }