ServiceClient.cpp
Go to the documentation of this file.
1 /*
2  * rosserial Service Client
3  */
4 
5 #include <ros.h>
6 #include <std_msgs/String.h>
7 #include <rosserial_mbed/Test.h>
8 
10 using rosserial_mbed::Test;
11 
13 
14 std_msgs::String str_msg;
15 ros::Publisher chatter("chatter", &str_msg);
16 
17 char hello[13] = "hello world!";
18 
19 int main() {
20  nh.initNode();
22  nh.advertise(chatter);
23  while (!nh.connected()) nh.spinOnce();
24  nh.loginfo("Startup complete");
25  while (1) {
26  Test::Request req;
27  Test::Response res;
28  req.input = hello;
29  client.call(req, res);
30  str_msg.data = res.output;
32  nh.spinOnce();
33  wait_ms(100);
34  }
35 }
36 
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
char hello[13]
ros::ServiceClient< Test::Request, Test::Response > client("test_srv")
Definition: client.py:1
std_msgs::String str_msg
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher chatter("chatter",&str_msg)
ros::NodeHandle nh
int main()


rosserial_mbed
Author(s): Gary Servin
autogenerated on Mon Jun 10 2019 14:53:26