APM:Libraries
GPIO_Navio.cpp
Go to the documentation of this file.
1 #include <AP_Common/AP_Common.h>
2 
3 #include "GPIO_Navio.h"
4 
5 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
6 
7 const unsigned Linux::GPIO_Sysfs::pin_table[] = {
8  [NAVIO_GPIO_A] = 21,
9  [NAVIO_GPIO_B] = 26,
10  [NAVIO_GPIO_C] = 20,
11  [NAVIO_GPIO_IO17] = 17,
12  [NAVIO_GPIO_IO18] = 18,
13  [NAVIO_GPIO_IO24] = 24,
14  [NAVIO_GPIO_IO25] = 25,
15  [NAVIO_GPIO_PCA_OE] = 27,
16  [NAVIO_GPIO_PPM_IN] = 4,
17 };
18 
20 
22  "GPIO pin_table must have the same size of entries in enum gpio_minnow");
23 
24 #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.