test_filter.cpp
Go to the documentation of this file.
1 // Bring in my package's API, which is what I'm testing
3 
4 
7 
8 // Bring in gtest
9 #include <gtest/gtest.h>
10 
11 
12 TEST(FilterTest, simpleMask)
13 {
14  const std::string msg1("123#");
15  const std::string msg2("124#");
16 
18 
19  EXPECT_TRUE(f1->pass(can::toframe(msg1)));
20  EXPECT_FALSE(f1->pass(can::toframe(msg2)));
21 }
22 
23 TEST(FilterTest, maskTests)
24 {
25  const std::string msg1("123#");
26  const std::string msg2("124#");
27  const std::string msg3("122#");
28 
32 
33  EXPECT_TRUE(f1->pass(can::toframe(msg1)));
34  EXPECT_FALSE(f1->pass(can::toframe(msg2)));
35  EXPECT_FALSE(f1->pass(can::toframe(msg3)));
36 
37 
38  EXPECT_TRUE(f2->pass(can::toframe(msg1)));
39  EXPECT_FALSE(f2->pass(can::toframe(msg2)));
40  EXPECT_TRUE(f2->pass(can::toframe(msg3)));
41 
42  EXPECT_FALSE(f3->pass(can::toframe(msg1)));
43  EXPECT_TRUE(f3->pass(can::toframe(msg2)));
44  EXPECT_TRUE(f3->pass(can::toframe(msg3)));
45 
46 }
47 
48 TEST(FilterTest, rangeTest)
49 {
50  const std::string msg1("120#");
51  const std::string msg2("125#");
52  const std::string msg3("130#");
53 
57 
58  EXPECT_TRUE(f1->pass(can::toframe(msg1)));
59  EXPECT_FALSE(f1->pass(can::toframe(msg2)));
60  EXPECT_FALSE(f1->pass(can::toframe(msg3)));
61 
62  EXPECT_FALSE(f2->pass(can::toframe(msg1)));
63  EXPECT_TRUE(f2->pass(can::toframe(msg2)));
64  EXPECT_TRUE(f2->pass(can::toframe(msg3)));
65 
66  EXPECT_TRUE(f3->pass(can::toframe(msg1)));
67  EXPECT_TRUE(f3->pass(can::toframe(msg2)));
68  EXPECT_FALSE(f3->pass(can::toframe(msg3)));
69 
70 }
71 
72 class Counter {
73 public:
74  size_t count_;
75  Counter(): count_(0) {}
76  void count(const can::Frame &frame) {
77  ++count_;
78  }
79 };
80 
81 TEST(FilterTest, listenerTest)
82 {
83 
84  Counter counter;
86 
88  filters.push_back(can::tofilter("123:FFE"));
89 
90  can::FrameListenerConstSharedPtr listener(new can::FilteredFrameListener(dummy,std::bind(&Counter::count, std::ref(counter), std::placeholders::_1), filters));
91 
92  can::Frame f1 = can::toframe("123#");
93  can::Frame f2 = can::toframe("124#");
94  can::Frame f3 = can::toframe("122#");
95 
96  dummy->send(f1);
97  EXPECT_EQ(1, counter.count_);
98  dummy->send(f2);
99  EXPECT_EQ(1, counter.count_);
100  dummy->send(f3);
101  EXPECT_EQ(2, counter.count_);
102 
103 }
104 
105 // Run all the tests that were declared with TEST()
106 int main(int argc, char **argv){
107 testing::InitGoogleTest(&argc, argv);
108 return RUN_ALL_TESTS();
109 }
FrameFilterSharedPtr tofilter(const T &ct)
size_t count_
Definition: test_filter.cpp:74
Frame toframe(const std::string &s)
Definition: string.cpp:119
std::shared_ptr< CommInterface > CommInterfaceSharedPtr
Definition: interface.h:175
CommInterface::FrameListenerConstSharedPtr FrameListenerConstSharedPtr
Definition: interface.h:176
std::vector< FrameFilterSharedPtr > FilterVector
Definition: filter.h:51
void count(const can::Frame &frame)
Definition: test_filter.cpp:76
TEST(FilterTest, simpleMask)
Definition: test_filter.cpp:12
void count(const can::Frame &msg)
int main(int argc, char **argv)
std::shared_ptr< FrameFilter > FrameFilterSharedPtr
Definition: filter.h:15


socketcan_interface
Author(s): Mathias Lüdtke
autogenerated on Mon Feb 28 2022 23:28:00