GPIO_RPI.cpp 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138
  1. #include <AP_HAL/AP_HAL.h>
  2. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
  3. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
  4. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
  5. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI || \
  6. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR
  7. #include <errno.h>
  8. #include <fcntl.h>
  9. #include <poll.h>
  10. #include <stdio.h>
  11. #include <stdlib.h>
  12. #include <string.h>
  13. #include <sys/mman.h>
  14. #include <sys/stat.h>
  15. #include <unistd.h>
  16. #include "GPIO.h"
  17. #include "Util_RPI.h"
  18. // Raspberry Pi GPIO memory
  19. #define BCM2708_PERI_BASE 0x20000000
  20. #define BCM2709_PERI_BASE 0x3F000000
  21. #define BCM2711_PERI_BASE 0xFE000000
  22. #define GPIO_BASE(address) (address + 0x200000)
  23. // GPIO setup. Always use INP_GPIO(x) before OUT_GPIO(x) or SET_GPIO_ALT(x,y)
  24. #define GPIO_MODE_IN(g) *(_gpio+((g)/10)) &= ~(7<<(((g)%10)*3))
  25. #define GPIO_MODE_OUT(g) *(_gpio+((g)/10)) |= (1<<(((g)%10)*3))
  26. #define GPIO_MODE_ALT(g,a) *(_gpio+(((g)/10))) |= (((a)<=3?(a)+4:(a)==4?3:2)<<(((g)%10)*3))
  27. #define GPIO_SET_HIGH *(_gpio+7) // sets bits which are 1
  28. #define GPIO_SET_LOW *(_gpio+10) // clears bits which are 1
  29. #define GPIO_GET(g) (*(_gpio+13)&(1<<g)) // 0 if LOW, (1<<g) if HIGH
  30. #define GPIO_RPI_MAX_NUMBER_PINS 32
  31. using namespace Linux;
  32. static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  33. GPIO_RPI::GPIO_RPI()
  34. {
  35. }
  36. void GPIO_RPI::init()
  37. {
  38. int rpi_version = UtilRPI::from(hal.util)->get_rpi_version();
  39. uint32_t gpio_address;
  40. if(rpi_version == 1) {
  41. gpio_address = GPIO_BASE(BCM2708_PERI_BASE);
  42. } else if (rpi_version == 2) {
  43. gpio_address = GPIO_BASE(BCM2709_PERI_BASE);
  44. } else {
  45. gpio_address = GPIO_BASE(BCM2711_PERI_BASE);
  46. }
  47. int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
  48. if (mem_fd < 0) {
  49. AP_HAL::panic("Can't open /dev/mem");
  50. }
  51. // mmap GPIO
  52. void *gpio_map = mmap(
  53. nullptr, // Any adddress in our space will do
  54. BLOCK_SIZE, // Map length
  55. PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory
  56. MAP_SHARED, // Shared with other processes
  57. mem_fd, // File to map
  58. gpio_address // Offset to GPIO peripheral
  59. );
  60. close(mem_fd); // No need to keep mem_fd open after mmap
  61. if (gpio_map == MAP_FAILED) {
  62. AP_HAL::panic("Can't open /dev/mem");
  63. }
  64. _gpio = (volatile uint32_t *)gpio_map;
  65. }
  66. void GPIO_RPI::pinMode(uint8_t pin, uint8_t output)
  67. {
  68. if (output == HAL_GPIO_INPUT) {
  69. GPIO_MODE_IN(pin);
  70. } else {
  71. GPIO_MODE_IN(pin);
  72. GPIO_MODE_OUT(pin);
  73. }
  74. }
  75. void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
  76. {
  77. if (output == HAL_GPIO_INPUT) {
  78. GPIO_MODE_IN(pin);
  79. } else if (output == HAL_GPIO_ALT) {
  80. GPIO_MODE_IN(pin);
  81. GPIO_MODE_ALT(pin, alt);
  82. } else {
  83. GPIO_MODE_IN(pin);
  84. GPIO_MODE_OUT(pin);
  85. }
  86. }
  87. uint8_t GPIO_RPI::read(uint8_t pin)
  88. {
  89. if (pin >= GPIO_RPI_MAX_NUMBER_PINS) {
  90. return 0;
  91. }
  92. uint32_t value = GPIO_GET(pin);
  93. return value ? 1: 0;
  94. }
  95. void GPIO_RPI::write(uint8_t pin, uint8_t value)
  96. {
  97. if (value == LOW) {
  98. GPIO_SET_LOW = 1 << pin;
  99. } else {
  100. GPIO_SET_HIGH = 1 << pin;
  101. }
  102. }
  103. void GPIO_RPI::toggle(uint8_t pin)
  104. {
  105. write(pin, !read(pin));
  106. }
  107. /* Alternative interface: */
  108. AP_HAL::DigitalSource* GPIO_RPI::channel(uint16_t n)
  109. {
  110. return new DigitalSource(n);
  111. }
  112. bool GPIO_RPI::usb_connected(void)
  113. {
  114. return false;
  115. }
  116. #endif