button.cpp 2.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192
  1. /*
  2. * Button Example for Rosserial
  3. */
  4. #include <rtthread.h>
  5. #include <board.h>
  6. #include <ros.h>
  7. #include <std_msgs/Bool.h>
  8. #define millis() ((unsigned long)rt_tick_get() * 1000 / RT_TICK_PER_SECOND)
  9. static ros::NodeHandle nh;
  10. static std_msgs::Bool pushed_msg;
  11. static ros::Publisher pub_button("pushed", &pushed_msg);
  12. static const int button_pin = GET_PIN(C, 8);
  13. static const int led_pin = GET_PIN(A, 5);
  14. static bool last_reading;
  15. static long last_debounce_time=0;
  16. static long debounce_delay=50;
  17. static bool published = true;
  18. static void rosserial_button_thread_entry(void *parameter)
  19. {
  20. nh.initNode();
  21. nh.advertise(pub_button);
  22. //initialize an LED output pin
  23. //and a input pin for our push button
  24. rt_pin_mode(led_pin, PIN_MODE_OUTPUT);
  25. rt_pin_mode(button_pin, PIN_MODE_INPUT);
  26. //Enable the pullup resistor on the button
  27. rt_pin_write(button_pin, PIN_HIGH);
  28. //The button is a normally button
  29. last_reading = ! rt_pin_read(button_pin);
  30. while (1)
  31. {
  32. bool reading = ! rt_pin_read(button_pin);
  33. if (last_reading!= reading){
  34. last_debounce_time = millis();
  35. published = false;
  36. }
  37. //if the button value has not changed for the debounce delay, we know its stable
  38. if ( !published && (millis() - last_debounce_time) > debounce_delay)
  39. {
  40. rt_pin_write(led_pin, reading);
  41. pushed_msg.data = reading;
  42. pub_button.publish(&pushed_msg);
  43. published = true;
  44. }
  45. last_reading = reading;
  46. nh.spinOnce();
  47. rt_thread_mdelay(500);
  48. }
  49. }
  50. static void rosserial_button_example(int argc,char *argv[])
  51. {
  52. rt_thread_t thread = rt_thread_create("r_btn", rosserial_button_thread_entry, RT_NULL, 1024, 25, 10);
  53. if(thread != RT_NULL)
  54. {
  55. rt_thread_startup(thread);
  56. rt_kprintf("[rosserial] New thread r_btn\n");
  57. }
  58. else
  59. {
  60. rt_kprintf("[rosserial] Failed to create thread r_btn\n");
  61. }
  62. }
  63. MSH_CMD_EXPORT(rosserial_button_example, roserial button example with UART);
  64. // If you are using Keil, you can ignore everything below
  65. // This is required
  66. // If you'd like to compile with scons which uses arm-none-eabi-gcc
  67. // extern "C" void __cxa_pure_virtual()
  68. // {
  69. // while (1);
  70. //}
  71. // Moreover, you need to add:
  72. // CXXFLAGS = CFLAGS + ' -fno-rtti'
  73. // in rtconfig.py for arm-none-eabi-gcc