00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <gtest/gtest.h>
00037
00038 #include "ros/ros.h"
00039 #include <test_roscpp/TestStringString.h>
00040
00041
00042 static int g_argc;
00043 static char** g_argv;
00044
00045 class ServiceAdvertiser : public testing::Test
00046 {
00047 public:
00048 ros::NodeHandle nh_;
00049 ros::ServiceServer srv_;
00050
00051 bool advertised_;
00052 bool failure_;
00053
00054 bool srvCallback(test_roscpp::TestStringString::Request &req,
00055 test_roscpp::TestStringString::Response &res)
00056 {
00057 ROS_INFO("in callback");
00058 if(!advertised_)
00059 {
00060 ROS_INFO("but not advertised!");
00061 failure_ = true;
00062 }
00063 return true;
00064 }
00065 protected:
00066 ServiceAdvertiser() {}
00067 void SetUp()
00068 {
00069 failure_ = false;
00070 advertised_ = false;
00071
00072 ASSERT_TRUE(g_argc == 1);
00073 }
00074
00075 bool adv()
00076 {
00077 ROS_INFO("advertising");
00078 srv_ = nh_.advertiseService("service_adv", &ServiceAdvertiser::srvCallback, this);
00079 ROS_INFO("advertised");
00080 return srv_;
00081 }
00082 bool unadv()
00083 {
00084 ROS_INFO("unadvertising");
00085 srv_.shutdown();
00086 ROS_INFO("unadvertised");
00087 return true;
00088 }
00089 };
00090
00091 TEST_F(ServiceAdvertiser, advUnadv)
00092 {
00093 advertised_ = true;
00094 ASSERT_TRUE(adv());
00095
00096 for(int i=0;i<100;i++)
00097 {
00098 if(advertised_)
00099 {
00100 ASSERT_TRUE(unadv());
00101 advertised_ = false;
00102 }
00103 else
00104 {
00105 advertised_ = true;
00106 ASSERT_TRUE(adv());
00107 }
00108
00109 ros::WallDuration(0.01).sleep();
00110 }
00111
00112 if(failure_)
00113 FAIL();
00114 else
00115 SUCCEED();
00116 }
00117
00118 int
00119 main(int argc, char** argv)
00120 {
00121 ros::init(argc, argv, "service_adv_unadv");
00122 testing::InitGoogleTest(&argc, argv);
00123 g_argc = argc;
00124 g_argv = argv;
00125 return RUN_ALL_TESTS();
00126 }
00127