to_socketcan_test.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016, Ivor Wanders
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the name of the copyright holder nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
29 
30 #include <can_msgs/Frame.h>
33 
34 #include <gtest/gtest.h>
35 #include <ros/ros.h>
36 #include <list>
37 #include <memory>
38 
40 {
41  public:
42  std::list<can::Frame> frames;
43 
45 
46  void frameCallback(const can::Frame& f)
47  {
48  frames.push_back(f);
49  }
50 };
51 
52 TEST(TopicToSocketCANTest, checkCorrectData)
53 {
54  ros::NodeHandle nh(""), nh_param("~");
55 
56  // create the dummy interface
57  can::DummyInterfaceSharedPtr driver_ = std::make_shared<can::DummyInterface>(true);
58 
59  // start the to topic bridge.
60  socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver_);
61  to_socketcan_bridge.setup();
62 
63  // init the driver to test stateListener (not checked automatically).
64  driver_->init("string_not_used", true);
65 
66  // register for messages on received_messages.
67  ros::Publisher publisher_ = nh.advertise<can_msgs::Frame>("sent_messages", 10);
68 
69  // create a frame collector.
70  frameCollector frame_collector_;
71 
72  // driver->createMsgListener(&frameCallback);
73  can::FrameListenerConstSharedPtr frame_listener_ = driver_->createMsgListener(
74 
75  std::bind(&frameCollector::frameCallback, &frame_collector_, std::placeholders::_1));
76 
77  // create a message
78  can_msgs::Frame msg;
79  msg.is_extended = true;
80  msg.is_rtr = false;
81  msg.is_error = false;
82  msg.id = 0x1337;
83  msg.dlc = 8;
84  for (uint8_t i=0; i < msg.dlc; i++)
85  {
86  msg.data[i] = i;
87  }
88 
89  msg.header.frame_id = "0"; // "0" for no frame.
90  msg.header.stamp = ros::Time::now();
91 
92  // send the can_frame::Frame message to the sent_messages topic.
93  publisher_.publish(msg);
94 
95  // give some time for the interface some time to process the message
96  ros::WallDuration(1.0).sleep();
97  ros::spinOnce();
98 
99  can_msgs::Frame received;
100  can::Frame f = frame_collector_.frames.back();
102 
103  EXPECT_EQ(received.id, msg.id);
104  EXPECT_EQ(received.dlc, msg.dlc);
105  EXPECT_EQ(received.is_extended, msg.is_extended);
106  EXPECT_EQ(received.is_rtr, msg.is_rtr);
107  EXPECT_EQ(received.is_error, msg.is_error);
108  EXPECT_EQ(received.data, msg.data);
109 }
110 
111 TEST(TopicToSocketCANTest, checkInvalidFrameHandling)
112 {
113  // - tries to send a non-extended frame with an id larger than 11 bits.
114  // that should not be sent.
115  // - verifies that sending one larger than 11 bits actually works.
116  // - tries sending a message with a dlc > 8 bytes, this should not be sent.
117  // sending with 8 bytes is verified by the checkCorrectData testcase.
118 
119  ros::NodeHandle nh(""), nh_param("~");
120 
121  // create the dummy interface
122  can::DummyInterfaceSharedPtr driver_ = std::make_shared<can::DummyInterface>(true);
123 
124  // start the to topic bridge.
125  socketcan_bridge::TopicToSocketCAN to_socketcan_bridge(&nh, &nh_param, driver_);
126  to_socketcan_bridge.setup();
127 
128  // register for messages on received_messages.
129  ros::Publisher publisher_ = nh.advertise<can_msgs::Frame>("sent_messages", 10);
130 
131  // create a frame collector.
132  frameCollector frame_collector_;
133 
134  // add callback to the dummy interface.
135  can::FrameListenerConstSharedPtr frame_listener_ = driver_->createMsgListener(
136  std::bind(&frameCollector::frameCallback, &frame_collector_, std::placeholders::_1));
137 
138  // create a message
139  can_msgs::Frame msg;
140  msg.is_extended = false;
141  msg.id = (1<<11)+1; // this is an illegal CAN packet... should not be sent.
142  msg.header.frame_id = "0"; // "0" for no frame.
143  msg.header.stamp = ros::Time::now();
144 
145  // send the can_frame::Frame message to the sent_messages topic.
146  publisher_.publish(msg);
147 
148  // give some time for the interface some time to process the message
149  ros::WallDuration(1.0).sleep();
150  ros::spinOnce();
151  EXPECT_EQ(frame_collector_.frames.size(), 0);
152 
153  msg.is_extended = true;
154  msg.id = (1<<11)+1; // now it should be alright.
155  // send the can_frame::Frame message to the sent_messages topic.
156  publisher_.publish(msg);
157  ros::WallDuration(1.0).sleep();
158  ros::spinOnce();
159  EXPECT_EQ(frame_collector_.frames.size(), 1);
160 
161  // wipe the frame queue.
162  frame_collector_.frames.clear();
163 
164 
165  // finally, check if frames with a dlc > 8 are discarded.
166  msg.dlc = 10;
167  publisher_.publish(msg);
168  ros::WallDuration(1.0).sleep();
169  ros::spinOnce();
170  EXPECT_EQ(frame_collector_.frames.size(), 0);
171 }
172 
173 int main(int argc, char **argv)
174 {
175  ros::init(argc, argv, "test_to_topic");
176  ros::NodeHandle nh;
177  ros::WallDuration(1.0).sleep();
178  testing::InitGoogleTest(&argc, argv);
179  return RUN_ALL_TESTS();
180 }
socketcan_to_topic.h
ros::WallDuration::sleep
bool sleep() const
dummy.h
ros::Publisher
can::Frame
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
socketcan_bridge::TopicToSocketCAN
Definition: topic_to_socketcan.h:37
frameCollector::frameCallback
void frameCallback(const can::Frame &f)
Definition: to_socketcan_test.cpp:46
can::DummyInterfaceSharedPtr
std::shared_ptr< DummyInterface > DummyInterfaceSharedPtr
ros::spinOnce
ROSCPP_DECL void spinOnce()
socketcan.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
topic_to_socketcan.h
f
f
socketcan_bridge::TopicToSocketCAN::setup
void setup()
Definition: topic_to_socketcan.cpp:42
main
int main(int argc, char **argv)
Definition: to_socketcan_test.cpp:173
TEST
TEST(TopicToSocketCANTest, checkCorrectData)
Definition: to_socketcan_test.cpp:52
frameCollector::frameCollector
frameCollector()
Definition: to_socketcan_test.cpp:44
frameCollector
Definition: to_socketcan_test.cpp:39
socketcan_bridge::convertSocketCANToMessage
void convertSocketCANToMessage(const can::Frame &f, can_msgs::Frame &m)
Definition: socketcan_to_topic.h:59
can::FrameListenerConstSharedPtr
CommInterface::FrameListenerConstSharedPtr FrameListenerConstSharedPtr
ros::WallDuration
frameCollector::frames
std::list< can::Frame > frames
Definition: to_socketcan_test.cpp:42
ros::NodeHandle
ros::Time::now
static Time now()


socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Wed Mar 2 2022 00:52:33