to_topic_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  */
28 
29 #include <can_msgs/Frame.h>
33 
34 #include <gtest/gtest.h>
35 #include <ros/ros.h>
36 #include <list>
37 #include <memory>
38 #include <string>
39 #include <vector>
40 
42 {
43  public:
44  std::list<can_msgs::Frame> messages;
45 
47 
48  void msgCallback(const can_msgs::Frame& f)
49  {
50  messages.push_back(f);
51  }
52 };
53 
54 std::string convertMessageToString(const can_msgs::Frame &msg, bool lc = true)
55 {
56  can::Frame f;
58  return can::tostring(f, lc);
59 }
60 
61 TEST(SocketCANToTopicTest, checkCorrectData)
62 {
63  ros::NodeHandle nh(""), nh_param("~");
64 
65  // create the dummy interface
66  can::DummyInterfaceSharedPtr driver_ = std::make_shared<can::DummyInterface>(true);
67 
68  // start the to topic bridge.
69  socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
70  to_topic_bridge.setup(); // initiate the message callbacks
71 
72  // init the driver to test stateListener (not checked automatically).
73  driver_->init("string_not_used", true);
74 
75  // create a frame collector.
76  msgCollector message_collector_;
77 
78  // register for messages on received_messages.
79  ros::Subscriber subscriber_ = nh.subscribe("received_messages", 1, &msgCollector::msgCallback, &message_collector_);
80 
81  // create a can frame
82  can::Frame f;
83  f.is_extended = true;
84  f.is_rtr = false;
85  f.is_error = false;
86  f.id = 0x1337;
87  f.dlc = 8;
88  for (uint8_t i=0; i < f.dlc; i++)
89  {
90  f.data[i] = i;
91  }
92 
93  // send the can frame to the driver
94  driver_->send(f);
95 
96  // give some time for the interface some time to process the message
97  ros::WallDuration(1.0).sleep();
98  ros::spinOnce();
99 
100  ASSERT_EQ(1, message_collector_.messages.size());
101 
102  // compare the received can_msgs::Frame message to the sent can::Frame.
103  can::Frame received;
104  can_msgs::Frame msg = message_collector_.messages.back();
106 
107  EXPECT_EQ(received.id, f.id);
108  EXPECT_EQ(received.dlc, f.dlc);
109  EXPECT_EQ(received.is_extended, f.is_extended);
110  EXPECT_EQ(received.is_rtr, f.is_rtr);
111  EXPECT_EQ(received.is_error, f.is_error);
112  EXPECT_EQ(received.data, f.data);
113 }
114 
115 TEST(SocketCANToTopicTest, checkInvalidFrameHandling)
116 {
117  // - tries to send a non-extended frame with an id larger than 11 bits.
118  // that should not be sent.
119  // - verifies that sending one larger than 11 bits actually works.
120 
121  // sending a message with a dlc > 8 is not possible as the DummyInterface
122  // causes a crash then.
123 
124  ros::NodeHandle nh(""), nh_param("~");
125 
126  // create the dummy interface
127  can::DummyInterfaceSharedPtr driver_ = std::make_shared<can::DummyInterface>(true);
128 
129  // start the to topic bridge.
130  socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
131  to_topic_bridge.setup(); // initiate the message callbacks
132 
133  // create a frame collector.
134  msgCollector message_collector_;
135 
136  // register for messages on received_messages.
137  ros::Subscriber subscriber_ = nh.subscribe("received_messages", 1, &msgCollector::msgCallback, &message_collector_);
138 
139  // create a message
140  can::Frame f;
141  f.is_extended = false;
142  f.id = (1<<11)+1; // this is an illegal CAN packet... should not be sent.
143 
144  // send the can::Frame over the driver.
145  // driver_->send(f);
146 
147  // give some time for the interface some time to process the message
148  ros::WallDuration(1.0).sleep();
149  ros::spinOnce();
150  EXPECT_EQ(message_collector_.messages.size(), 0);
151 
152  f.is_extended = true;
153  f.id = (1<<11)+1; // now it should be alright.
154 
155  driver_->send(f);
156  ros::WallDuration(1.0).sleep();
157  ros::spinOnce();
158  EXPECT_EQ(message_collector_.messages.size(), 1);
159 }
160 
161 TEST(SocketCANToTopicTest, checkCorrectCanIdFilter)
162 {
163  ros::NodeHandle nh(""), nh_param("~");
164 
165  // create the dummy interface
166  can::DummyInterfaceSharedPtr driver_ = std::make_shared<can::DummyInterface>(true);
167 
168  // create can_id vector with id that should be passed and published to ros
169  std::vector<unsigned int> pass_can_ids;
170  pass_can_ids.push_back(0x1337);
171 
172  // start the to topic bridge.
173  socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
174  to_topic_bridge.setup(can::tofilters(pass_can_ids)); // initiate the message callbacks
175 
176  // init the driver to test stateListener (not checked automatically).
177  driver_->init("string_not_used", true);
178 
179  // create a frame collector.
180  msgCollector message_collector_;
181 
182  // register for messages on received_messages.
183  ros::Subscriber subscriber_ = nh.subscribe("received_messages", 1, &msgCollector::msgCallback, &message_collector_);
184 
185  // create a can frame
186  can::Frame f;
187  f.is_extended = true;
188  f.is_rtr = false;
189  f.is_error = false;
190  f.id = 0x1337;
191  f.dlc = 8;
192  for (uint8_t i=0; i < f.dlc; i++)
193  {
194  f.data[i] = i;
195  }
196 
197  // send the can frame to the driver
198  driver_->send(f);
199 
200  // give some time for the interface some time to process the message
201  ros::WallDuration(1.0).sleep();
202  ros::spinOnce();
203 
204  ASSERT_EQ(1, message_collector_.messages.size());
205 
206  // compare the received can_msgs::Frame message to the sent can::Frame.
207  can::Frame received;
208  can_msgs::Frame msg = message_collector_.messages.back();
210 
211  EXPECT_EQ(received.id, f.id);
212  EXPECT_EQ(received.dlc, f.dlc);
213  EXPECT_EQ(received.is_extended, f.is_extended);
214  EXPECT_EQ(received.is_rtr, f.is_rtr);
215  EXPECT_EQ(received.is_error, f.is_error);
216  EXPECT_EQ(received.data, f.data);
217 }
218 
219 TEST(SocketCANToTopicTest, checkInvalidCanIdFilter)
220 {
221  ros::NodeHandle nh(""), nh_param("~");
222 
223  // create the dummy interface
224  can::DummyInterfaceSharedPtr driver_ = std::make_shared<can::DummyInterface>(true);
225 
226  // create can_id vector with id that should not be received on can bus
227  std::vector<unsigned int> pass_can_ids;
228  pass_can_ids.push_back(0x300);
229 
230  // start the to topic bridge.
231  socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
232  to_topic_bridge.setup(can::tofilters(pass_can_ids)); // initiate the message callbacks
233 
234  // init the driver to test stateListener (not checked automatically).
235  driver_->init("string_not_used", true);
236 
237  // create a frame collector.
238  msgCollector message_collector_;
239 
240  // register for messages on received_messages.
241  ros::Subscriber subscriber_ = nh.subscribe("received_messages", 1, &msgCollector::msgCallback, &message_collector_);
242 
243  // create a can frame
244  can::Frame f;
245  f.is_extended = true;
246  f.is_rtr = false;
247  f.is_error = false;
248  f.id = 0x1337;
249  f.dlc = 8;
250  for (uint8_t i=0; i < f.dlc; i++)
251  {
252  f.data[i] = i;
253  }
254 
255  // send the can frame to the driver
256  driver_->send(f);
257 
258  // give some time for the interface some time to process the message
259  ros::WallDuration(1.0).sleep();
260  ros::spinOnce();
261 
262  EXPECT_EQ(0, message_collector_.messages.size());
263 }
264 
265 TEST(SocketCANToTopicTest, checkMaskFilter)
266 {
267  ros::NodeHandle nh(""), nh_param("~");
268 
269  // create the dummy interface
270  can::DummyInterfaceSharedPtr driver_ = std::make_shared<can::DummyInterface>(true);
271 
272  // setup filter
274  filters.push_back(can::tofilter("300:ffe"));
275 
276  // start the to topic bridge.
277  socketcan_bridge::SocketCANToTopic to_topic_bridge(&nh, &nh_param, driver_);
278  to_topic_bridge.setup(filters); // initiate the message callbacks
279 
280  // init the driver to test stateListener (not checked automatically).
281  driver_->init("string_not_used", true);
282 
283  // create a frame collector.
284  msgCollector message_collector_;
285 
286  // register for messages on received_messages.
287  ros::Subscriber subscriber_ = nh.subscribe("received_messages", 10, &msgCollector::msgCallback, &message_collector_);
288 
289  const std::string pass1("300#1234"), nopass1("302#9999"), pass2("301#5678");
290 
291  // send the can framew to the driver
292  driver_->send(can::toframe(pass1));
293  driver_->send(can::toframe(nopass1));
294  driver_->send(can::toframe(pass2));
295 
296  // give some time for the interface some time to process the message
297  ros::WallDuration(1.0).sleep();
298  ros::spinOnce();
299 
300  // compare the received can_msgs::Frame message to the sent can::Frame.
301  ASSERT_EQ(2, message_collector_.messages.size());
302  EXPECT_EQ(pass1, convertMessageToString(message_collector_.messages.front()));
303  EXPECT_EQ(pass2, convertMessageToString(message_collector_.messages.back()));
304 }
305 
306 int main(int argc, char **argv)
307 {
308  ros::init(argc, argv, "test_to_topic");
309  ros::NodeHandle nh;
310  ros::WallDuration(1.0).sleep();
311  testing::InitGoogleTest(&argc, argv);
312  return RUN_ALL_TESTS();
313 }
socketcan_to_topic.h
ros::WallDuration::sleep
bool sleep() const
can::tofilters
FilteredFrameListener::FilterVector tofilters(const T &v)
dummy.h
can::Frame
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
can::Header::is_extended
unsigned int is_extended
msgCollector::msgCollector
msgCollector()
Definition: to_topic_test.cpp:46
ros.h
msgCollector
Definition: to_topic_test.cpp:41
can::DummyInterfaceSharedPtr
std::shared_ptr< DummyInterface > DummyInterfaceSharedPtr
ros::spinOnce
ROSCPP_DECL void spinOnce()
can::Frame::dlc
unsigned char dlc
socketcan.h
topic_to_socketcan.h
f
f
can::FilteredFrameListener::FilterVector
std::vector< FrameFilterSharedPtr > FilterVector
can::tostring
std::string tostring(const Frame &f, bool lc)
main
int main(int argc, char **argv)
Definition: to_topic_test.cpp:306
msgCollector::msgCallback
void msgCallback(const can_msgs::Frame &f)
Definition: to_topic_test.cpp:48
can::Header::is_rtr
unsigned int is_rtr
can::Header::id
unsigned int id
can::Frame::data
std::array< value_type, 8 > data
msgCollector::messages
std::list< can_msgs::Frame > messages
Definition: to_topic_test.cpp:44
convertMessageToString
std::string convertMessageToString(const can_msgs::Frame &msg, bool lc=true)
Definition: to_topic_test.cpp:54
socketcan_bridge::convertMessageToSocketCAN
void convertMessageToSocketCAN(const can_msgs::Frame &m, can::Frame &f)
Definition: topic_to_socketcan.h:53
can::tofilter
FrameFilterSharedPtr tofilter(const char *s)
can::toframe
Frame toframe(const std::string &s)
socketcan_bridge::SocketCANToTopic::setup
void setup()
Definition: socketcan_to_topic.cpp:60
can::Header::is_error
unsigned int is_error
ros::WallDuration
socketcan_bridge::SocketCANToTopic
Definition: socketcan_to_topic.h:38
ros::NodeHandle
ros::Subscriber
TEST
TEST(SocketCANToTopicTest, checkCorrectData)
Definition: to_topic_test.cpp:61


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