ServiceServer.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial Service Server
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 int i;
00013 void callback(const Test::Request & req, Test::Response & res) {
00014     if ((i++)%2)
00015         res.output = "hello";
00016     else
00017         res.output = "world";
00018 }
00019 
00020 ros::ServiceServer<Test::Request, Test::Response> server("test_srv",&callback);
00021 
00022 std_msgs::String str_msg;
00023 ros::Publisher chatter("chatter", &str_msg);
00024 
00025 char hello[13] = "hello world!";
00026 
00027 int main(void) {
00028     nh.initNode();
00029     nh.advertiseService(server);
00030     nh.advertise(chatter);
00031 
00032 
00033     while (1) {
00034         str_msg.data = hello;
00035         chatter.publish( &str_msg );
00036         nh.spinOnce();
00037         wait_ms(10);
00038     }
00039 }
00040 


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