unittest_update_filter.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <string>
19 #include <memory>
20 #include <boost/bind.hpp>
21 
22 #include <gtest/gtest.h>
23 #include <gmock/gmock.h>
24 
25 #include <ros/ros.h>
26 
28 #include <prbt_hardware_support/ModbusMsgInStamped.h>
31 
32 namespace mf = message_filters;
33 
35 
37 {
38 using ::testing::_;
39 using ::testing::AtLeast;
40 using ::testing::Return;
41 using ::testing::Throw;
42 using namespace prbt_hardware_support;
43 
45 {
46  public:
47  MOCK_METHOD1(modbusInMsgCallback, void(ModbusMsgInStampedConstPtr msg));
48 };
49 
51 {
52  public:
53  TestPublisher(const Publisher& rhs):
54  ros::Publisher::Publisher(rhs)
55  {
56  }
57 
58  template <typename M>
59  void publishAndSpin(const boost::shared_ptr<M>& message) const
60  {
61  this->publish(message);
62  ros::spinOnce();
63  }
64 };
65 
69 class UpdateFilterTest : public testing::Test
70 {
71 public:
72  void SetUp() override;
73  void TearDown() override;
74  std::shared_ptr<CallbackReceiver> callback_receiver_;
75 };
76 
77 void UpdateFilterTest::SetUp()
78 {
79  this->callback_receiver_.reset(new CallbackReceiver());
80 }
81 
82 void UpdateFilterTest::TearDown()
83 {
84  this->callback_receiver_ = nullptr;
85 }
86 
90 TEST_F(UpdateFilterTest, testFilteringThroughSubscriber)
91 {
92  std::string test_topic_name = "/test_topic";
93 
94  ros::NodeHandle nh;
95  ros::Publisher pub = nh.advertise<ModbusMsgInStamped>(test_topic_name,1);
96  TestPublisher test_pub(pub);
97  message_filters::Subscriber<ModbusMsgInStamped> modbus_sub(nh, test_topic_name,1);
98 
99  mf::UpdateFilter<ModbusMsgInStamped> update_filter(modbus_sub);
100 
101  // Register to modbus callback
102  update_filter.registerCallback(boost::bind(&CallbackReceiver::modbusInMsgCallback, this->callback_receiver_, _1));
103 
104  // 3 Messages will be send, only two are new
105  EXPECT_CALL(*(this->callback_receiver_.get()), modbusInMsgCallback(_)).Times(3);
106 
107  ModbusMsgInStampedPtr msg(new ModbusMsgInStamped());
108 
109  msg->header.stamp = ros::Time(1);
110  test_pub.publishAndSpin(msg); // Should pass - CALL 1
111  test_pub.publishAndSpin(msg);
112 
113  msg->header.stamp = ros::Time(2);
114  test_pub.publishAndSpin(msg); // Should pass - CALL 2
115  test_pub.publishAndSpin(msg);
116  test_pub.publishAndSpin(msg);
117 
118  msg->header.stamp = ros::Time(3);
119  test_pub.publishAndSpin(msg); // Should pass - CALL 3
120 }
121 
122 
123 } // namespace update_filter_test
124 
125 int main(int argc, char *argv[])
126 {
127  ros::init(argc, argv, "unittest_update_filter");
128  testing::InitGoogleTest(&argc, argv);
129  ros::Time::init(); // Needed on message construction
130  return RUN_ALL_TESTS();
131 }
msg
TEST_F(BrakeTestRequiredIntegrationTest, testBrakeTestAnnouncement)
Filters consecutive messages with the same timestamp. Only the first message passes, all consecutive are dropped. It is templated on the message type to be filtered.
Definition: update_filter.h:41
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char *argv[])
std::shared_ptr< CallbackReceiver > callback_receiver_
static void init()
void publishAndSpin(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spinOnce()
UpdateFilterTest tests the UpdateFilter class.
Connection registerCallback(const C &callback)


prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:17