GPIO_Navio.cpp 685 B

123456789101112131415161718192021222324
  1. #include <AP_HAL/AP_HAL_Boards.h>
  2. #include "GPIO_Navio.h"
  3. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
  4. const unsigned Linux::GPIO_Sysfs::pin_table[] = {
  5. [NAVIO_GPIO_A] = 21,
  6. [NAVIO_GPIO_B] = 26,
  7. [NAVIO_GPIO_C] = 20,
  8. [NAVIO_GPIO_IO17] = 17,
  9. [NAVIO_GPIO_IO18] = 18,
  10. [NAVIO_GPIO_IO24] = 24,
  11. [NAVIO_GPIO_IO25] = 25,
  12. [NAVIO_GPIO_PCA_OE] = 27,
  13. [NAVIO_GPIO_PPM_IN] = 4,
  14. };
  15. const uint8_t Linux::GPIO_Sysfs::n_pins = _NAVIO_GPIO_MAX;
  16. static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _NAVIO_GPIO_MAX,
  17. "GPIO pin_table must have the same size of entries in enum gpio_navio");
  18. #endif