ExampleService.cpp
Go to the documentation of this file.
1 /*
2  * rosserial_embeddedlinux service server example
3  *
4  * Advertises a service it offers. Prints the string sent to the service
5  * and responds with an alternating string.
6  * The service request can be sent from the ROS command line with e.g.
7  * $ xxx
8  */
9 
10 #include <ros.h>
11 #include <std_msgs/String.h>
12 #include <rosserial_examples_msgs/Test.h>
13 #include <stdio.h>
14 
16 using rosserial_examples::Test;
17 #define ROSSRVR_IP "192.168.15.122"
18 
19 int i=0;
20 void svcCallback(const Test::Request & req, Test::Response & res){
21  if((i++)%2)
22  res.output = "hello";
23  else
24  res.output = "ros";
25  printf("Service request message: \"%s\" received, responding with: %s", res.output);
26 }
28 
29 int main()
30 {
31  nh.initNode(ROSSRVR_IP);
33 
34  while(1) {
35  nh.spinOnce();
36  sleep(1);
37  }
38 }
i
int i
Definition: ExampleService.cpp:19
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
ROSSRVR_IP
#define ROSSRVR_IP
Definition: ExampleService.cpp:17
svcCallback
void svcCallback(const Test::Request &req, Test::Response &res)
Definition: ExampleService.cpp:20
server
ros::ServiceServer< Test::Request, Test::Response > server("test_srv",&svcCallback)
nh
ros::NodeHandle nh
Definition: ExampleService.cpp:15
main
int main()
Definition: ExampleService.cpp:29
ros::ServiceServer
ros::NodeHandle


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Wed Mar 2 2022 00:58:06