20 #include <boost/bind.hpp> 22 #include <gtest/gtest.h> 23 #include <gmock/gmock.h> 28 #include <prbt_hardware_support/ModbusMsgInStamped.h> 39 using ::testing::AtLeast;
40 using ::testing::Return;
41 using ::testing::Throw;
47 MOCK_METHOD1(modbusInMsgCallback,
void(
const ModbusMsgInStampedConstPtr&
msg));
60 this->publish(message);
71 void SetUp()
override;
72 void TearDown()
override;
76 void UpdateFilterTest::SetUp()
81 void UpdateFilterTest::TearDown()
83 this->callback_receiver_ =
nullptr;
91 std::string test_topic_name =
"/test_topic";
101 update_filter.
registerCallback(boost::bind(&CallbackReceiver::modbusInMsgCallback, this->callback_receiver_, _1));
104 EXPECT_CALL(*(this->callback_receiver_.get()), modbusInMsgCallback(_)).Times(3);
106 ModbusMsgInStampedPtr
msg(
new ModbusMsgInStamped());
109 test_pub.publishAndSpin(msg);
110 test_pub.publishAndSpin(msg);
113 test_pub.publishAndSpin(msg);
114 test_pub.publishAndSpin(msg);
115 test_pub.publishAndSpin(msg);
118 test_pub.publishAndSpin(msg);
123 int main(
int argc,
char* argv[])
125 ros::init(argc, argv,
"unittest_update_filter");
126 testing::InitGoogleTest(&argc, argv);
128 return RUN_ALL_TESTS();
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.
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
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spinOnce()
UpdateFilterTest tests the UpdateFilter class.
TestPublisher(const Publisher &rhs)
Connection registerCallback(const C &callback)