APM:Libraries
GPIO_Navio2.cpp
Go to the documentation of this file.
1 #include <AP_Common/AP_Common.h>
2 
3 #include "GPIO_Navio2.h"
4 
5 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
6 
7 const unsigned Linux::GPIO_Sysfs::pin_table[] = {
8  [NAVIO2_GPIO_PWM1] = 500,
9  [NAVIO2_GPIO_PWM2] = 501,
10  [NAVIO2_GPIO_PWM3] = 502,
11  [NAVIO2_GPIO_PWM4] = 503,
12  [NAVIO2_GPIO_PWM5] = 504,
13  [NAVIO2_GPIO_PWM6] = 505,
14  [NAVIO2_GPIO_PWM7] = 506,
15  [NAVIO2_GPIO_PWM8] = 507,
16  [NAVIO2_GPIO_PWM9] = 508,
17  [NAVIO2_GPIO_PWM10] = 509,
18  [NAVIO2_GPIO_PWM11] = 510,
19  [NAVIO2_GPIO_PWM12] = 511,
20  [NAVIO2_GPIO_PWM13] = 512,
21  [NAVIO2_GPIO_PWM14] = 513,
22  [NAVIO2_GPIO_IO17] = 17,
23  [NAVIO2_GPIO_IO18] = 18,
24  [NAVIO2_GPIO_RED] = 4,
25  [NAVIO2_GPIO_GREEN] = 27,
26  [NAVIO2_GPIO_BLUE] = 6,
27 };
28 
30 
32  "GPIO pin_table must have the same size of entries in enum gpio_minnow");
33 
34 #endif
static const uint8_t n_pins
Definition: GPIO_Sysfs.h:33
static const unsigned pin_table[]
Definition: GPIO_Sysfs.h:32
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
Common definitions and utility routines for the ArduPilot libraries.