6 #include <std_msgs/String.h> 7 #include <rosserial_mbed/Test.h> 10 using rosserial_mbed::Test;
17 char hello[13] =
"hello world!";
23 while (!nh.connected()) nh.spinOnce();
24 nh.loginfo(
"Startup complete");
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
ros::ServiceClient< Test::Request, Test::Response > client("test_srv")
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher chatter("chatter",&str_msg)