APM:Libraries
GPIO_Edge.cpp
Go to the documentation of this file.
1 #include <AP_Common/AP_Common.h>
2 
3 #include "GPIO_Edge.h"
4 
5 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
6 
7 const unsigned Linux::GPIO_Sysfs::pin_table[] = {
8  [EDGE_GPIO_PWM1] = 500,
9  [EDGE_GPIO_PWM2] = 501,
10  [EDGE_GPIO_PWM3] = 502,
11  [EDGE_GPIO_PWM4] = 503,
12  [EDGE_GPIO_PWM5] = 504,
13  [EDGE_GPIO_PWM6] = 505,
14  [EDGE_GPIO_PWM7] = 506,
15  [EDGE_GPIO_PWM8] = 507,
16  [EDGE_GPIO_PWM9] = 508,
17  [EDGE_GPIO_PWM10] = 509,
18  [EDGE_GPIO_PWM11] = 510,
19  [EDGE_GPIO_PWM12] = 511,
20  [EDGE_GPIO_HEAT_ENABLE] = 26,
21 };
22 
24 
26  "GPIO pin_table must have the same size of entries in enum gpio_minnow");
27 
28 #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.