Go to the documentation of this file.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 "ros/ros.h"
00037 #include <test_roscpp/TestStringString.h>
00038
00039 bool caseFlip(test_roscpp::TestStringString::Request &req,
00040 test_roscpp::TestStringString::Response &res)
00041 {
00042
00043 res.str = req.str;
00044 for (size_t i = 0; i < res.str.length(); i++)
00045 {
00046 char c = res.str[i];
00047 if (islower(c))
00048 c = toupper(c);
00049 else if (isupper(c))
00050 c = tolower(c);
00051 res.str[i] = c;
00052 }
00053 return true;
00054 }
00055
00056 bool caseFlipLongRunning(test_roscpp::TestStringString::Request &req,
00057 test_roscpp::TestStringString::Response &res)
00058 {
00059 caseFlip(req, res);
00060
00061 ros::Duration(2).sleep();
00062 return true;
00063 }
00064
00065 bool caseFlipUnadvertise(test_roscpp::TestStringString::Request &req,
00066 test_roscpp::TestStringString::Response &res, ros::ServiceServer& srv)
00067 {
00068 caseFlip(req, res);
00069
00070 srv.shutdown();
00071
00072 ros::Duration(2).sleep();
00073 return true;
00074 }
00075
00076
00077 int
00078 main(int argc, char** argv)
00079 {
00080 ros::init(argc, argv, "service_adv");
00081 ros::NodeHandle nh;
00082
00083 ros::ServiceServer srv1, srv2, srv3;
00084 srv1 = nh.advertiseService("service_adv", caseFlip);
00085 srv2 = nh.advertiseService("service_adv_long", caseFlipLongRunning);
00086 srv3 = nh.advertiseService<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>("service_adv_unadv_in_callback", boost::bind(caseFlipUnadvertise, _1, _2, boost::ref(srv3)));
00087 ros::spin();
00088 }
00089