GPIOTest.cpp 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127
  1. #include <stdio.h>
  2. #include <unistd.h>
  3. #include <AP_Common/AP_Common.h>
  4. #include <AP_HAL_Linux/AP_HAL_Linux.h>
  5. #include <AP_Menu/AP_Menu.h>
  6. void setup();
  7. void loop();
  8. int parse_gpio_pin_number(uint8_t argc, const Menu::arg *argv);
  9. #define MENU_FUNC(func) FUNCTOR_BIND(&commands, &MenuCommands::func, int8_t, uint8_t, const Menu::arg *)
  10. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  11. int parse_gpio_pin_number(uint8_t argc, const Menu::arg *argv) {
  12. if (argc != 2) {
  13. fprintf(stderr, "Input and output commands take only one argument, which is the GPIO pin number\n");
  14. return -1;
  15. }
  16. long int pin = argv[1].i;
  17. if (pin <= 0) {
  18. fprintf(stderr, "Invalid pin number: %ld\n", pin);
  19. return -1;
  20. }
  21. return pin;
  22. }
  23. static int8_t test_gpio_input(uint8_t argc, const Menu::arg *argv, bool use_channel) {
  24. AP_HAL::DigitalSource *ch = nullptr;
  25. int pin = parse_gpio_pin_number(argc, argv);
  26. if (pin <= 0) return -1;
  27. if (use_channel) {
  28. ch = hal.gpio->channel(pin);
  29. ch->mode(HAL_GPIO_INPUT);
  30. } else {
  31. hal.gpio->pinMode(pin, HAL_GPIO_INPUT);
  32. }
  33. hal.console->printf("Ok, I'll start reading pin number %d and printing the value read on intervals of 1 second.", pin);
  34. while (1) {
  35. hal.console->printf("%u ", use_channel ? ch->read() : hal.gpio->read(pin));
  36. sleep(1);
  37. }
  38. return 0;
  39. }
  40. static int8_t test_gpio_output(uint8_t argc, const Menu::arg *argv, bool use_channel) {
  41. AP_HAL::DigitalSource *ch = nullptr;
  42. int pin = parse_gpio_pin_number(argc, argv);
  43. if (pin <= 0) return -1;
  44. if (use_channel) {
  45. ch = hal.gpio->channel(pin);
  46. ch->mode(HAL_GPIO_OUTPUT);
  47. } else {
  48. hal.gpio->pinMode(pin, HAL_GPIO_OUTPUT);
  49. }
  50. hal.console->printf("Now I'll start toggling the signal on the pin number %d on intervals of 1 second."
  51. " It's recommended to verify that the signal is reaching it (e.g. by using a LED)\n", pin);
  52. uint8_t signal = 0;
  53. while (1) {
  54. signal ^= 1;
  55. if (use_channel) {
  56. ch->write(signal);
  57. } else {
  58. hal.gpio->write(pin, signal);
  59. }
  60. sleep(1);
  61. }
  62. return 0;
  63. }
  64. class MenuCommands {
  65. public:
  66. int8_t gpio_input(uint8_t argc, const Menu::arg *argv) {
  67. return ::test_gpio_input(argc, argv, false);
  68. }
  69. int8_t gpio_output(uint8_t argc, const Menu::arg *argv) {
  70. return ::test_gpio_output(argc, argv, false);
  71. }
  72. int8_t gpio_input_channel(uint8_t argc, const Menu::arg *argv) {
  73. hal.console->printf("GPIO Input using digital source\n");
  74. return test_gpio_input(argc, argv, true);
  75. }
  76. int8_t gpio_output_channel(uint8_t argc, const Menu::arg *argv) {
  77. hal.console->printf("GPIO Output using digital source\n");
  78. return test_gpio_output(argc, argv, true);
  79. }
  80. };
  81. MenuCommands commands;
  82. const struct Menu::command test_menu_commands[] = {
  83. {"input", MENU_FUNC(gpio_input)},
  84. {"output", MENU_FUNC(gpio_output)},
  85. {"input_ch", MENU_FUNC(gpio_input_channel)},
  86. {"output_ch", MENU_FUNC(gpio_output_channel)}
  87. };
  88. MENU(main_menu, "GPIOTest: Please select one of the operations followed by the GPIO pin number", test_menu_commands);
  89. void setup(void)
  90. {
  91. Menu::set_port(hal.console);
  92. hal.console->set_blocking_writes(true);
  93. while (1) {
  94. main_menu.run();
  95. }
  96. }
  97. void loop(void)
  98. {
  99. }
  100. AP_HAL_MAIN();