service_client.cpp 1.7 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667
  1. /*
  2. * rosserial Service Client
  3. */
  4. #include <rtthread.h>
  5. #include <ros.h>
  6. #include <std_msgs/String.h>
  7. #include "port/Test.h"
  8. static ros::NodeHandle nh;
  9. using rosserial_rtt::Test;
  10. static ros::ServiceClient<Test::Request, Test::Response> client("test_srv");
  11. static std_msgs::String str_msg;
  12. static ros::Publisher chatter("chatter", &str_msg);
  13. static char hello[13] = "hello world!";
  14. static void rosserial_client_thread_entry(void *parameter)
  15. {
  16. nh.initNode();
  17. nh.serviceClient(client);
  18. nh.advertise(chatter);
  19. while(!nh.connected()) nh.spinOnce();
  20. nh.loginfo("Startup complete");
  21. while (1)
  22. {
  23. Test::Request req;
  24. Test::Response res;
  25. req.input = hello;
  26. client.call(req, res);
  27. str_msg.data = res.output;
  28. chatter.publish( &str_msg );
  29. nh.spinOnce();
  30. rt_thread_mdelay(10);
  31. }
  32. }
  33. static void rosserial_client_example(int argc,char *argv[])
  34. {
  35. rt_thread_t thread = rt_thread_create("r_client", rosserial_client_thread_entry, RT_NULL, 1024, 25, 10);
  36. if(thread != RT_NULL)
  37. {
  38. rt_thread_startup(thread);
  39. rt_kprintf("[rosserial] New thread r_client\n");
  40. }
  41. else
  42. {
  43. rt_kprintf("[rosserial] Failed to create thread r_client\n");
  44. }
  45. }
  46. MSH_CMD_EXPORT(rosserial_client_example, roserial publish and subscribe with UART);
  47. // If you are using Keil, you can ignore everything below
  48. // This is required
  49. // If you'd like to compile with scons which uses arm-none-eabi-gcc
  50. // extern "C" void __cxa_pure_virtual()
  51. // {
  52. // while (1);
  53. //}
  54. // Moreover, you need to add:
  55. // CXXFLAGS = CFLAGS + ' -fno-rtti'
  56. // in rtconfig.py for arm-none-eabi-gcc