ServiceServer.cpp
Go to the documentation of this file.
1 /*
2  * rosserial Service Server
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 
12 int i;
13 void callback(const Test::Request & req, Test::Response & res) {
14  if ((i++)%2)
15  res.output = "hello";
16  else
17  res.output = "world";
18 }
19 
21 
22 std_msgs::String str_msg;
23 ros::Publisher chatter("chatter", &str_msg);
24 
25 char hello[13] = "hello world!";
26 
27 int main(void) {
28  nh.initNode();
29  nh.advertiseService(server);
30  nh.advertise(chatter);
31 
32 
33  while (1) {
34  str_msg.data = hello;
36  nh.spinOnce();
37  wait_ms(10);
38  }
39 }
40 
std_msgs::String str_msg
void publish(const boost::shared_ptr< M > &message) const
void callback(const Test::Request &req, Test::Response &res)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
char hello[13]
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int i
ros::ServiceServer< Test::Request, Test::Response > server("test_srv",&callback)
int main(void)
ros::NodeHandle nh
ros::Publisher chatter("chatter",&str_msg)


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