GPIO_Edge.cpp 803 B

12345678910111213141516171819202122232425262728
  1. #include <AP_HAL/AP_HAL_Boards.h>
  2. #include "GPIO_Edge.h"
  3. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
  4. const unsigned Linux::GPIO_Sysfs::pin_table[] = {
  5. [EDGE_GPIO_PWM1] = 500,
  6. [EDGE_GPIO_PWM2] = 501,
  7. [EDGE_GPIO_PWM3] = 502,
  8. [EDGE_GPIO_PWM4] = 503,
  9. [EDGE_GPIO_PWM5] = 504,
  10. [EDGE_GPIO_PWM6] = 505,
  11. [EDGE_GPIO_PWM7] = 506,
  12. [EDGE_GPIO_PWM8] = 507,
  13. [EDGE_GPIO_PWM9] = 508,
  14. [EDGE_GPIO_PWM10] = 509,
  15. [EDGE_GPIO_PWM11] = 510,
  16. [EDGE_GPIO_PWM12] = 511,
  17. [EDGE_GPIO_HEAT_ENABLE] = 26,
  18. };
  19. const uint8_t Linux::GPIO_Sysfs::n_pins = _EDGE_GPIO_MAX;
  20. static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _EDGE_GPIO_MAX,
  21. "GPIO pin_table must have the same size of entries in enum edge");
  22. #endif