hello_world_serial.cpp 1.1 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647
  1. #include <rtthread.h>
  2. #include <ros.h>
  3. #include <std_msgs/String.h>
  4. static ros::NodeHandle nh;
  5. static std_msgs::String str_msg;
  6. static ros::Publisher chatter("chatter", &str_msg);
  7. static char hello_msg[13] = "hello world!";
  8. static void rosserial_thread_entry(void *parameter)
  9. {
  10. nh.initNode();
  11. nh.advertise(chatter);
  12. while (1)
  13. {
  14. if ( nh.connected() )
  15. {
  16. str_msg.data = hello_msg;
  17. chatter.publish( &str_msg );
  18. }
  19. /*
  20. else
  21. {
  22. rt_kprintf("[rosserial] Not Connected");
  23. }
  24. */
  25. nh.spinOnce();
  26. rt_thread_delay(RT_TICK_PER_SECOND);
  27. }
  28. }
  29. static void rosserial_hello_world_serial_example(int argc,char *argv[])
  30. {
  31. rt_thread_t thread = rt_thread_create("rosserial", rosserial_thread_entry, RT_NULL, 1024, 25, 10);
  32. if(thread != RT_NULL)
  33. {
  34. rt_thread_startup(thread);
  35. rt_kprintf("[rosserial] New thread rosserial\n");
  36. }
  37. else
  38. {
  39. rt_kprintf("[rosserial] Failed to create thread rosserial\n");
  40. }
  41. }
  42. MSH_CMD_EXPORT(rosserial_hello_world_serial_example, roserial hello world example with UART);