GPIO_BBB.cpp 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124
  1. #include <AP_HAL/AP_HAL.h>
  2. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
  3. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || \
  4. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI || \
  5. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE || \
  6. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
  7. #include "GPIO.h"
  8. #include <stdio.h>
  9. #include <stdlib.h>
  10. #include <string.h>
  11. #include <errno.h>
  12. #include <unistd.h>
  13. #include <fcntl.h>
  14. #include <poll.h>
  15. #include <sys/mman.h>
  16. #include <sys/stat.h>
  17. using namespace Linux;
  18. GPIO_BBB::GPIO_BBB()
  19. {}
  20. void GPIO_BBB::init()
  21. {
  22. #if LINUX_GPIO_NUM_BANKS == 4
  23. int mem_fd;
  24. // Enable all GPIO banks
  25. // Without this, access to deactivated banks (i.e. those with no clock source set up) will (logically) fail with SIGBUS
  26. // Idea taken from https://groups.google.com/forum/#!msg/beagleboard/OYFp4EXawiI/Mq6s3sg14HoJ
  27. uint8_t bank_enable[3] = { 5, 65, 105 };
  28. int export_fd = open("/sys/class/gpio/export", O_WRONLY | O_CLOEXEC);
  29. if (export_fd == -1) {
  30. AP_HAL::panic("unable to open /sys/class/gpio/export");
  31. }
  32. for (uint8_t i=0; i<3; i++) {
  33. dprintf(export_fd, "%u\n", (unsigned)bank_enable[i]);
  34. }
  35. close(export_fd);
  36. /* open /dev/mem */
  37. if ((mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC)) < 0) {
  38. printf("can't open /dev/mem \n");
  39. exit (-1);
  40. }
  41. /* mmap GPIO */
  42. off_t offsets[LINUX_GPIO_NUM_BANKS] = { GPIO0_BASE, GPIO1_BASE, GPIO2_BASE, GPIO3_BASE };
  43. for (uint8_t i=0; i<LINUX_GPIO_NUM_BANKS; i++) {
  44. gpio_bank[i].base = (volatile unsigned *)mmap(0, GPIO_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, offsets[i]);
  45. if ((char *)gpio_bank[i].base == MAP_FAILED) {
  46. AP_HAL::panic("unable to map GPIO bank");
  47. }
  48. gpio_bank[i].oe = gpio_bank[i].base + GPIO_OE;
  49. gpio_bank[i].in = gpio_bank[i].base + GPIO_IN;
  50. gpio_bank[i].out = gpio_bank[i].base + GPIO_OUT;
  51. }
  52. close(mem_fd);
  53. #endif // LINUX_GPIO_NUM_BANKS
  54. }
  55. void GPIO_BBB::pinMode(uint8_t pin, uint8_t output)
  56. {
  57. uint8_t bank = pin/32;
  58. uint8_t bankpin = pin & 0x1F;
  59. if (bank >= LINUX_GPIO_NUM_BANKS) {
  60. return;
  61. }
  62. if (output == HAL_GPIO_INPUT) {
  63. *gpio_bank[bank].oe |= (1U<<bankpin);
  64. } else {
  65. *gpio_bank[bank].oe &= ~(1U<<bankpin);
  66. }
  67. }
  68. uint8_t GPIO_BBB::read(uint8_t pin) {
  69. uint8_t bank = pin/32;
  70. uint8_t bankpin = pin & 0x1F;
  71. if (bank >= LINUX_GPIO_NUM_BANKS) {
  72. return 0;
  73. }
  74. return *gpio_bank[bank].in & (1U<<bankpin) ? HIGH : LOW;
  75. }
  76. void GPIO_BBB::write(uint8_t pin, uint8_t value)
  77. {
  78. uint8_t bank = pin/32;
  79. uint8_t bankpin = pin & 0x1F;
  80. if (bank >= LINUX_GPIO_NUM_BANKS) {
  81. return;
  82. }
  83. if (value == LOW) {
  84. *gpio_bank[bank].out &= ~(1U<<bankpin);
  85. } else {
  86. *gpio_bank[bank].out |= 1U<<bankpin;
  87. }
  88. }
  89. void GPIO_BBB::toggle(uint8_t pin)
  90. {
  91. write(pin, !read(pin));
  92. }
  93. /* Alternative interface: */
  94. AP_HAL::DigitalSource* GPIO_BBB::channel(uint16_t n) {
  95. return new DigitalSource(n);
  96. }
  97. bool GPIO_BBB::usb_connected(void)
  98. {
  99. return false;
  100. }
  101. #endif // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF ||
  102. // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD ||
  103. // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI ||
  104. // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE ||
  105. // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET