tf.cpp 1.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566
  1. /*
  2. * rosserial Time and TF Example
  3. * Publishes a transform at current time
  4. */
  5. #include <rtthread.h>
  6. #include <ros.h>
  7. #include <ros/time.h>
  8. #include <tf/transform_broadcaster.h>
  9. ros::NodeHandle nh;
  10. geometry_msgs::TransformStamped t;
  11. tf::TransformBroadcaster broadcaster;
  12. char base_link[] = "/base_link";
  13. char odom[] = "/odom";
  14. static void rosserial_tf_thread_entry(void *parameter)
  15. {
  16. nh.initNode();
  17. broadcaster.init(nh);
  18. while (1)
  19. {
  20. t.header.frame_id = odom;
  21. t.child_frame_id = base_link;
  22. t.transform.translation.x = 1.0;
  23. t.transform.rotation.x = 0.0;
  24. t.transform.rotation.y = 0.0;
  25. t.transform.rotation.z = 0.0;
  26. t.transform.rotation.w = 1.0;
  27. t.header.stamp = nh.now();
  28. broadcaster.sendTransform(t);
  29. nh.spinOnce();
  30. rt_thread_mdelay(10);
  31. }
  32. }
  33. static void rosserial_tf_example(int argc,char *argv[])
  34. {
  35. rt_thread_t thread = rt_thread_create("r_tf", rosserial_tf_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_tf\n");
  40. }
  41. else
  42. {
  43. rt_kprintf("[rosserial] Failed to create thread r_tf\n");
  44. }
  45. }
  46. MSH_CMD_EXPORT(rosserial_tf_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