service_server.cpp 1.7 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374
  1. /*
  2. * rosserial Service Server
  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 int i;
  11. static void callback(const Test::Request & req, Test::Response & res){
  12. if((i++)%2)
  13. {
  14. res.output = "hello";
  15. }
  16. else
  17. {
  18. res.output = "world";
  19. }
  20. }
  21. static ros::ServiceServer<Test::Request, Test::Response> server("test_srv", &callback);
  22. static std_msgs::String str_msg;
  23. static ros::Publisher chatter("chatter", &str_msg);
  24. static char hello[13] = "hello world!";
  25. static void rosserial_server_thread_entry(void *parameter)
  26. {
  27. nh.initNode();
  28. nh.advertiseService(server);
  29. nh.advertise(chatter);
  30. while (1)
  31. {
  32. str_msg.data = hello;
  33. chatter.publish( &str_msg );
  34. nh.spinOnce();
  35. rt_thread_mdelay(10);
  36. }
  37. }
  38. static void rosserial_server_example(int argc,char *argv[])
  39. {
  40. rt_thread_t thread = rt_thread_create("r_server", rosserial_server_thread_entry, RT_NULL, 1024, 25, 10);
  41. if(thread != RT_NULL)
  42. {
  43. rt_thread_startup(thread);
  44. rt_kprintf("[rosserial] New thread r_server\n");
  45. }
  46. else
  47. {
  48. rt_kprintf("[rosserial] Failed to create thread r_server\n");
  49. }
  50. }
  51. MSH_CMD_EXPORT(rosserial_server_example, roserial publish and subscribe with UART);
  52. // If you are using Keil, you can ignore everything below
  53. // This is required
  54. // If you'd like to compile with scons which uses arm-none-eabi-gcc
  55. // extern "C" void __cxa_pure_virtual()
  56. // {
  57. // while (1);
  58. //}
  59. // Moreover, you need to add:
  60. // CXXFLAGS = CFLAGS + ' -fno-rtti'
  61. // in rtconfig.py for arm-none-eabi-gcc