Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #include <ros.h>
00011 #include <std_msgs/String.h>
00012 #include <rosserial_examples_msgs/Test.h>
00013 #include <stdio.h>
00014
00015 ros::NodeHandle nh;
00016 using rosserial_examples::Test;
00017 #define ROSSRVR_IP "192.168.15.122"
00018
00019 int i=0;
00020 void svcCallback(const Test::Request & req, Test::Response & res){
00021 if((i++)%2)
00022 res.output = "hello";
00023 else
00024 res.output = "ros";
00025 printf("Service request message: \"%s\" received, responding with: %s", res.output);
00026 }
00027 ros::ServiceServer<Test::Request, Test::Response> server("test_srv",&svcCallback);
00028
00029 int main()
00030 {
00031 nh.initNode(ROSSRVR_IP);
00032 nh.advertiseService(server);
00033
00034 while(1) {
00035 nh.spinOnce();
00036 sleep(1);
00037 }
00038 }