ExampleServiceClient.cpp
Go to the documentation of this file.
1 /*
2  * rosserial_embeddedlinux service client example
3  *
4  * Calls a service offered by a ROS service server and publishes what it receives from
5  * the service server to the chatter topic. It also prints the received service response.
6  *
7  * You can run a suitable service on ROS with:
8  * $ rosrun rosserial_embeddedlinux client.py
9  *
10  * When you run this program on the embedded linux system, client.py on the ROS workstation
11  * will ask you to respond with a string. The string you give it will be passed back to this
12  * service client, which will print and publish it.
13  */
14 
15 #include <ros.h>
16 #include <std_msgs/String.h>
17 #include <rosserial_embeddedlinux/Test.h>
18 #include <stdio.h>
19 
21 using rosserial_embeddedlinux::Test;
22 #define ROSSRVR_IP "192.168.15.149"
23 
25 
26 std_msgs::String str_msg;
27 ros::Publisher chatter("chatter", &str_msg);
28 
29 char hello[13] = "hello world!";
30 
31 int main()
32 {
33  nh.initNode(ROSSRVR_IP);
35  nh.advertise(chatter);
36  while(!nh.connected()) nh.spinOnce();
37  printf("Startup complete\n");
38  while (1) {
39  Test::Request req;
40  Test::Response res;
41  req.input = hello;
42  client.call(req, res);
43  printf("Service responded with \"%s\"\n", res.output);
44  str_msg.data = res.output;
46  nh.spinOnce();
47  sleep(1);
48  }
49 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publish(const boost::shared_ptr< M > &message) const
int main()
std_msgs::String str_msg
ros::NodeHandle nh
char hello[13]
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceClient< Test::Request, Test::Response > client("test_srv")
#define ROSSRVR_IP
ros::Publisher chatter("chatter",&str_msg)


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Mon Jun 10 2019 14:53:23