GPIO_Navio2.cpp 1.0 KB

12345678910111213141516171819202122232425262728293031323334
  1. #include <AP_HAL/AP_HAL_Boards.h>
  2. #include "GPIO_Navio2.h"
  3. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
  4. const unsigned Linux::GPIO_Sysfs::pin_table[] = {
  5. [NAVIO2_GPIO_PWM1] = 500,
  6. [NAVIO2_GPIO_PWM2] = 501,
  7. [NAVIO2_GPIO_PWM3] = 502,
  8. [NAVIO2_GPIO_PWM4] = 503,
  9. [NAVIO2_GPIO_PWM5] = 504,
  10. [NAVIO2_GPIO_PWM6] = 505,
  11. [NAVIO2_GPIO_PWM7] = 506,
  12. [NAVIO2_GPIO_PWM8] = 507,
  13. [NAVIO2_GPIO_PWM9] = 508,
  14. [NAVIO2_GPIO_PWM10] = 509,
  15. [NAVIO2_GPIO_PWM11] = 510,
  16. [NAVIO2_GPIO_PWM12] = 511,
  17. [NAVIO2_GPIO_PWM13] = 512,
  18. [NAVIO2_GPIO_PWM14] = 513,
  19. [NAVIO2_GPIO_IO17] = 17,
  20. [NAVIO2_GPIO_IO18] = 18,
  21. [NAVIO2_GPIO_RED] = 4,
  22. [NAVIO2_GPIO_GREEN] = 27,
  23. [NAVIO2_GPIO_BLUE] = 6,
  24. };
  25. const uint8_t Linux::GPIO_Sysfs::n_pins = _NAVIO2_GPIO_MAX;
  26. static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _NAVIO2_GPIO_MAX,
  27. "GPIO pin_table must have the same size of entries in enum gpio_navio2");
  28. #endif