00001 #include "ros_lib/ros/subscriber.h" 00002 #include <gtest/gtest.h> 00003 00004 00005 bool callbackCalled; 00006 unsigned char buffer[1]; 00007 00008 class DummyMsg 00009 { 00010 public: 00011 int serialize(unsigned char *outbuffer) const { return 0; } 00012 int deserialize(unsigned char *inbuffer) { return 0; } 00013 const char * getType() { return ""; } 00014 const char * getMD5() { return ""; } 00015 }; 00016 00017 class DummyClass 00018 { 00019 public: 00020 static void staticCallback(const DummyMsg& msg) 00021 { 00022 callbackCalled = true; 00023 } 00024 void memberCallback(const DummyMsg& msg) 00025 { 00026 callbackCalled = true; 00027 } 00028 }; 00029 00030 00031 TEST(TestSubscriber, testStaticCallback) 00032 { 00033 ros::Subscriber<DummyMsg> sub("topic_name", &DummyClass::staticCallback); 00034 00035 callbackCalled = false; 00036 sub.callback(buffer); 00037 ASSERT_TRUE(callbackCalled); 00038 } 00039 00040 TEST(TestSubscriber, testMemberCallback) 00041 { 00042 DummyClass cl; 00043 ros::Subscriber<DummyMsg, DummyClass> sub("topic_name", &DummyClass::memberCallback, &cl); 00044 00045 callbackCalled = false; 00046 sub.callback(buffer); 00047 ASSERT_TRUE(callbackCalled); 00048 } 00049 00050 00051 int main(int argc, char **argv) 00052 { 00053 testing::InitGoogleTest(&argc, argv); 00054 return RUN_ALL_TESTS(); 00055 }