to_topic_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/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   // create the dummy interface
00056   boost::shared_ptr<can::DummyInterface> driver_ = boost::make_shared<can::DummyInterface>(true);
00057 
00058   // start the to topic bridge.
00059   socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
00060   to_topic_bridge.setup();  // initiate the message callbacks
00061 
00062   // init the driver to test stateListener (not checked automatically).
00063   driver_->init("string_not_used", true);
00064 
00065   // create a frame collector.
00066   msgCollector message_collector_;
00067 
00068   // register for messages on received_messages.
00069   ros::Subscriber subscriber_ = nh.subscribe("received_messages", 1, &msgCollector::msgCallback, &message_collector_);
00070 
00071   // create a can frame
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   // send the can frame to the driver
00084   driver_->send(f);
00085 
00086   // give some time for the interface some time to process the message
00087   ros::WallDuration(1.0).sleep();
00088   ros::spinOnce();
00089 
00090   // compare the received can_msgs::Frame message to the sent can::Frame.
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   // - tries to send a non-extended frame with an id larger than 11 bits.
00104   //   that should not be sent.
00105   // - verifies that sending one larger than 11 bits actually works.
00106 
00107   // sending a message with a dlc > 8 is not possible as the DummyInterface
00108   // causes a crash then.
00109 
00110   ros::NodeHandle nh(""), nh_param("~");
00111 
00112   // create the dummy interface
00113   boost::shared_ptr<can::DummyInterface> driver_ = boost::make_shared<can::DummyInterface>(true);
00114 
00115   // start the to topic bridge.
00116   socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
00117   to_topic_bridge.setup();  // initiate the message callbacks
00118 
00119   // create a frame collector.
00120   msgCollector message_collector_;
00121 
00122   // register for messages on received_messages.
00123   ros::Subscriber subscriber_ = nh.subscribe("received_messages", 1, &msgCollector::msgCallback, &message_collector_);
00124 
00125   // create a message
00126   can::Frame f;
00127   f.is_extended = false;
00128   f.id = (1<<11)+1;  // this is an illegal CAN packet... should not be sent.
00129 
00130   // send the can::Frame over the driver.
00131   // driver_->send(f);
00132 
00133   // give some time for the interface some time to process the message
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;  // now it should be alright.
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 }


socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Thu Jun 6 2019 20:44:10