APM:Libraries
GPIO_Minnow.cpp
Go to the documentation of this file.
1 #include <AP_Common/AP_Common.h>
2 
3 #include "GPIO_Minnow.h"
4 
5 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
6 
7 const unsigned Linux::GPIO_Sysfs::pin_table[] = {
8  [MINNOW_GPIO_SPI_CS] = 476,
9  [MINNOW_GPIO_SPI_MISO] = 477,
10  [MINNOW_GPIO_SPI_MOSI] = 478,
11  [MINNOW_GPIO_SPI_CLK] = 479,
12  [MINNOW_GPIO_I2C_SCL] = 499,
13  [MINNOW_GPIO_I2C_SDA] = 498,
14  [MINNOW_GPIO_UART2_TXD] = 485,
15  [MINNOW_GPIO_UART2_RXD] = 484,
16  [MINNOW_GPIO_S5_0] = 338,
17  [MINNOW_GPIO_S5_1] = 339,
18  [MINNOW_GPIO_S5_2] = 340,
19  [MINNOW_GPIO_UART1_TXD] = 481,
20  [MINNOW_GPIO_UART1_RXD] = 480,
21  [MINNOW_GPIO_UART1_CTS] = 483,
22  [MINNOW_GPIO_UART1_RTS] = 482,
23  [MINNOW_GPIO_I2S_CLK] = 472,
24  [MINNOW_GPIO_I2S_FRM] = 473,
25  [MINNOW_GPIO_I2S_DO] = 475,
26  [MINNOW_GPIO_I2S_DI] = 474,
27  [MINNOW_GPIO_PWM0] = 504,
28  [MINNOW_GPIO_PWM1] = 505,
29  [MINNOW_GPIO_IBL_8254] = 464,
30 };
31 
33 
35  "GPIO pin_table must have the same size of entries in enum gpio_minnow");
36 
37 #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.