ExampleServiceClient.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial_embeddedlinux service client example
00003  *
00004  * Calls a service offered by a ROS service server and publishes what it receives from
00005  * the service server to the chatter topic. It also prints the received service response.
00006  *
00007  * You can run a suitable service on ROS with:
00008  * $ rosrun rosserial_embeddedlinux client.py
00009  *
00010  * When you run this program on the embedded linux system, client.py on the ROS workstation
00011  * will ask you to respond with a string. The string you give it will be passed back to this
00012  * service client, which will print and publish it.
00013  */
00014 
00015 #include <ros.h>
00016 #include <std_msgs/String.h>
00017 #include <rosserial_embeddedlinux/Test.h>
00018 #include <stdio.h>
00019 
00020 ros::NodeHandle  nh;
00021 using rosserial_embeddedlinux::Test;
00022 #define ROSSRVR_IP "192.168.15.149"
00023 
00024 ros::ServiceClient<Test::Request, Test::Response> client("test_srv");
00025 
00026 std_msgs::String str_msg;
00027 ros::Publisher chatter("chatter", &str_msg);
00028 
00029 char hello[13] = "hello world!";
00030 
00031 int main()
00032 {
00033           nh.initNode(ROSSRVR_IP);
00034           nh.serviceClient(client);
00035           nh.advertise(chatter);
00036           while(!nh.connected()) nh.spinOnce();
00037           printf("Startup complete\n");
00038           while (1) {
00039                   Test::Request req;
00040                   Test::Response res;
00041                   req.input = hello;
00042                   client.call(req, res);
00043                   printf("Service responded with \"%s\"\n", res.output);
00044                   str_msg.data = res.output;
00045                   chatter.publish( &str_msg );
00046                   nh.spinOnce();
00047                   sleep(1);
00048           }
00049 }


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Thu Jun 6 2019 19:56:29