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(const ModbusMsgInStampedConstPtr& msg));
48 };
49 
51 {
52 public:
53  TestPublisher(const Publisher& rhs) : ros::Publisher::Publisher(rhs)
54  {
55  }
56 
57  template <typename M>
58  void publishAndSpin(const boost::shared_ptr<M>& message) const
59  {
60  this->publish(message);
61  ros::spinOnce();
62  }
63 };
64 
68 class UpdateFilterTest : public testing::Test
69 {
70 public:
71  void SetUp() override;
72  void TearDown() override;
73  std::shared_ptr<CallbackReceiver> callback_receiver_;
74 };
75 
76 void UpdateFilterTest::SetUp()
77 {
78  this->callback_receiver_.reset(new CallbackReceiver());
79 }
80 
81 void UpdateFilterTest::TearDown()
82 {
83  this->callback_receiver_ = nullptr;
84 }
85 
89 TEST_F(UpdateFilterTest, testFilteringThroughSubscriber)
90 {
91  std::string test_topic_name = "/test_topic";
92 
93  ros::NodeHandle nh;
94  ros::Publisher pub = nh.advertise<ModbusMsgInStamped>(test_topic_name, 1);
95  TestPublisher test_pub(pub);
96  message_filters::Subscriber<ModbusMsgInStamped> modbus_sub(nh, test_topic_name, 1);
97 
98  mf::UpdateFilter<ModbusMsgInStamped> update_filter(modbus_sub);
99 
100  // Register to modbus callback
101  update_filter.registerCallback(boost::bind(&CallbackReceiver::modbusInMsgCallback, this->callback_receiver_, _1));
102 
103  // 3 Messages will be send, only two are new
104  EXPECT_CALL(*(this->callback_receiver_.get()), modbusInMsgCallback(_)).Times(3);
105 
106  ModbusMsgInStampedPtr msg(new ModbusMsgInStamped());
107 
108  msg->header.stamp = ros::Time(1);
109  test_pub.publishAndSpin(msg); // Should pass - CALL 1
110  test_pub.publishAndSpin(msg);
111 
112  msg->header.stamp = ros::Time(2);
113  test_pub.publishAndSpin(msg); // Should pass - CALL 2
114  test_pub.publishAndSpin(msg);
115  test_pub.publishAndSpin(msg);
116 
117  msg->header.stamp = ros::Time(3);
118  test_pub.publishAndSpin(msg); // Should pass - CALL 3
119 }
120 
121 } // namespace update_filter_test
122 
123 int main(int argc, char* argv[])
124 {
125  ros::init(argc, argv, "unittest_update_filter");
126  testing::InitGoogleTest(&argc, argv);
127  ros::Time::init(); // Needed on message construction
128  return RUN_ALL_TESTS();
129 }
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:40
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_
void publishAndSpin(const boost::shared_ptr< M > &message) const
static void init()
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 Mon Feb 28 2022 23:14:34