ServiceClient.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial Service Client
00003  */
00004 
00005 #include <ros.h>
00006 #include <std_msgs/String.h>
00007 #include <rosserial_mbed/Test.h>
00008 
00009 ros::NodeHandle  nh;
00010 using rosserial_mbed::Test;
00011 
00012 ros::ServiceClient<Test::Request, Test::Response> client("test_srv");
00013 
00014 std_msgs::String str_msg;
00015 ros::Publisher chatter("chatter", &str_msg);
00016 
00017 char hello[13] = "hello world!";
00018 
00019 int main() {
00020     nh.initNode();
00021     nh.serviceClient(client);
00022     nh.advertise(chatter);
00023     while (!nh.connected()) nh.spinOnce();
00024     nh.loginfo("Startup complete");
00025     while (1) {
00026         Test::Request req;
00027         Test::Response res;
00028         req.input = hello;
00029         client.call(req, res);
00030         str_msg.data = res.output;
00031         chatter.publish( &str_msg );
00032         nh.spinOnce();
00033         wait_ms(100);
00034     }
00035 }
00036 


rosserial_mbed
Author(s): Gary Servin
autogenerated on Sat Oct 7 2017 03:08:46