to_socketcan_test.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2016, Ivor Wanders
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the name of the copyright holder nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
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   // create the dummy interface
00055   boost::shared_ptr<can::DummyInterface> driver_ = boost::make_shared<can::DummyInterface>(true);
00056 
00057   // start the to topic bridge.
00058   socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver_);
00059   to_socketcan_bridge.setup();
00060 
00061   // init the driver to test stateListener (not checked automatically).
00062   driver_->init("string_not_used", true);
00063 
00064   // register for messages on received_messages.
00065   ros::Publisher publisher_ = nh.advertise<can_msgs::Frame>("sent_messages", 10);
00066 
00067   // create a frame collector.
00068   frameCollector frame_collector_;
00069 
00070   //  driver->createMsgListener(&frameCallback);
00071   can::CommInterface::FrameListener::Ptr frame_listener_ = driver_->createMsgListener(
00072             can::CommInterface::FrameDelegate(&frame_collector_, &frameCollector::frameCallback));
00073 
00074   // create a message
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";  // "0" for no frame.
00087   msg.header.stamp = ros::Time::now();
00088 
00089   // send the can_frame::Frame message to the sent_messages topic.
00090   publisher_.publish(msg);
00091 
00092   // give some time for the interface some time to process the message
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   // - tries to send a non-extended frame with an id larger than 11 bits.
00109   //   that should not be sent.
00110   // - verifies that sending one larger than 11 bits actually works.
00111   // - tries sending a message with a dlc > 8 bytes, this should not be sent.
00112   //   sending with 8 bytes is verified by the checkCorrectData testcase.
00113 
00114   ros::NodeHandle nh(""), nh_param("~");
00115 
00116   // create the dummy interface
00117   boost::shared_ptr<can::DummyInterface> driver_ = boost::make_shared<can::DummyInterface>(true);
00118 
00119   // start the to topic bridge.
00120   socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver_);
00121   to_socketcan_bridge.setup();
00122 
00123   // register for messages on received_messages.
00124   ros::Publisher publisher_ = nh.advertise<can_msgs::Frame>("sent_messages", 10);
00125 
00126   // create a frame collector.
00127   frameCollector frame_collector_;
00128 
00129   //  add callback to the dummy interface.
00130   can::CommInterface::FrameListener::Ptr frame_listener_ = driver_->createMsgListener(
00131           can::CommInterface::FrameDelegate(&frame_collector_, &frameCollector::frameCallback));
00132 
00133   // create a message
00134   can_msgs::Frame msg;
00135   msg.is_extended = false;
00136   msg.id = (1<<11)+1;  // this is an illegal CAN packet... should not be sent.
00137   msg.header.frame_id = "0";  // "0" for no frame.
00138   msg.header.stamp = ros::Time::now();
00139 
00140   // send the can_frame::Frame message to the sent_messages topic.
00141   publisher_.publish(msg);
00142 
00143   // give some time for the interface some time to process the message
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;  // now it should be alright.
00150   // send the can_frame::Frame message to the sent_messages topic.
00151   publisher_.publish(msg);
00152   ros::WallDuration(1.0).sleep();
00153   ros::spinOnce();
00154   EXPECT_EQ(frame_collector_.frames.size(), 1);
00155 
00156   // wipe the frame queue.
00157   frame_collector_.frames.clear();
00158 
00159 
00160   // finally, check if frames with a dlc > 8 are discarded.
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 }


socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Sun Sep 3 2017 03:11:00