blink_class.cpp 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  1. #include <rtthread.h>
  2. #include <board.h>
  3. #include <ros.h>
  4. #include <std_srvs/SetBool.h>
  5. #include <std_msgs/UInt16.h>
  6. #define LED0_PIN GET_PIN(A, 5)
  7. #define millis() ((unsigned long)rt_tick_get() * 1000 / RT_TICK_PER_SECOND)
  8. static ros::NodeHandle nh;
  9. class Blinker
  10. {
  11. public:
  12. Blinker(rt_base_t pin, uint16_t period)
  13. : pin_(pin), period_(period),
  14. subscriber_("set_blink_period", &Blinker::set_period_callback, this),
  15. service_server_("activate_blinker", &Blinker::service_callback, this)
  16. {
  17. active_ = RT_TRUE;
  18. }
  19. void init(ros::NodeHandle& nh)
  20. {
  21. rt_pin_mode(pin_, PIN_MODE_OUTPUT);
  22. nh.subscribe(subscriber_);
  23. nh.advertiseService(service_server_);
  24. }
  25. void run()
  26. {
  27. if(active_ && ((millis() - last_time_) >= period_))
  28. {
  29. last_time_ = millis();
  30. rt_pin_write(pin_, !rt_pin_read(pin_));
  31. }
  32. }
  33. void set_period_callback(const std_msgs::UInt16& msg)
  34. {
  35. period_ = msg.data;
  36. }
  37. void service_callback(const std_srvs::SetBool::Request& req,
  38. std_srvs::SetBool::Response& res)
  39. {
  40. active_ = req.data;
  41. res.success = true;
  42. if(req.data)
  43. {
  44. res.message = "Blinker ON";
  45. }
  46. else
  47. {
  48. res.message = "Blinker OFF";
  49. }
  50. }
  51. private:
  52. const rt_base_t pin_;
  53. rt_bool_t active_;
  54. uint16_t period_;
  55. uint32_t last_time_;
  56. ros::Subscriber<std_msgs::UInt16, Blinker> subscriber_;
  57. ros::ServiceServer<std_srvs::SetBool::Request, std_srvs::SetBool::Response, Blinker> service_server_;
  58. };
  59. static Blinker blinker(LED0_PIN, 500);
  60. static void rosserial_blink_class_thread_entry(void *parameter)
  61. {
  62. nh.initNode();
  63. blinker.init(nh);
  64. while (1)
  65. {
  66. blinker.run();
  67. nh.spinOnce();
  68. rt_thread_mdelay(500);
  69. }
  70. }
  71. static void rosserial_blink_class_example(int argc,char *argv[])
  72. {
  73. rt_thread_t thread = rt_thread_create("r_blinkc", rosserial_blink_class_thread_entry, RT_NULL, 1024, 25, 10);
  74. if(thread != RT_NULL)
  75. {
  76. rt_thread_startup(thread);
  77. rt_kprintf("[rosserial] New thread r_blinkc\n");
  78. }
  79. else
  80. {
  81. rt_kprintf("[rosserial] Failed to create thread r_blinkc\n");
  82. }
  83. }
  84. MSH_CMD_EXPORT(rosserial_blink_class_example, roserial blink class example with UART);
  85. // If you are using Keil, you can ignore everything below
  86. // This is required
  87. // If you'd like to compile with scons which uses arm-none-eabi-gcc
  88. // extern "C" void __cxa_pure_virtual()
  89. // {
  90. // while (1);
  91. //}
  92. // Moreover, you need to add:
  93. // CXXFLAGS = CFLAGS + ' -fno-rtti'
  94. // in rtconfig.py for arm-none-eabi-gcc