mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
HAL_ChibiOS: auto-generate GPIO table from hwdef.dat
This commit is contained in:
parent
fbe8166c71
commit
867e7ebf71
@ -21,33 +21,13 @@
|
||||
|
||||
using namespace ChibiOS;
|
||||
|
||||
// GPIO pin table from hwdef.dat
|
||||
static struct gpio_entry {
|
||||
uint8_t pin_num;
|
||||
bool enabled;
|
||||
uint8_t pwm_num;
|
||||
ioline_t pal_line;
|
||||
} _gpio_tab[] = {
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
|
||||
{0, PAL_LINE(GPIOB, 7U)},
|
||||
{1, PAL_LINE(GPIOB, 6U)},
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3
|
||||
// pin numbers chosen to match px4 build
|
||||
{0, true, PAL_LINE(GPIOE, 12U)}, // LED
|
||||
{1, true, PAL_LINE(GPIOB, 0U)},
|
||||
{50, false, PAL_LINE(GPIOE, 14U)},
|
||||
{51, false, PAL_LINE(GPIOE, 13U)},
|
||||
{52, false, PAL_LINE(GPIOE, 11U)},
|
||||
{53, false, PAL_LINE(GPIOE, 9U)},
|
||||
{54, true, PAL_LINE(GPIOD, 13U)},
|
||||
{55, true, PAL_LINE(GPIOD, 14U)},
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV4
|
||||
{0, true, PAL_LINE(GPIOB, 1U)}, // green
|
||||
{1, true, PAL_LINE(GPIOB, 3U)}, // blue
|
||||
{2, true, PAL_LINE(GPIOB, 11U)}, // red
|
||||
{3, true, PAL_LINE(GPIOC, 3U)}, // safety
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
|
||||
{0, true, PAL_LINE(GPIOA, 8U)}, // run LED
|
||||
#endif
|
||||
};
|
||||
} _gpio_tab[] = HAL_GPIO_PINS;
|
||||
|
||||
#define NUM_PINS ARRAY_SIZE_SIMPLE(_gpio_tab)
|
||||
#define PIN_ENABLED(pin) ((pin)<NUM_PINS && _gpio_tab[pin].enabled)
|
||||
@ -124,16 +104,12 @@ GPIO::GPIO()
|
||||
void GPIO::init()
|
||||
{
|
||||
extStart(&EXTD1, &extcfg);
|
||||
// auto-disable pins being used for PWM output based on BRD_PWM_COUNT parameter
|
||||
uint8_t pwm_count = AP_BoardConfig::get_pwm_count();
|
||||
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
|
||||
uint8_t pin_num = _gpio_tab[i].pin_num;
|
||||
if (pin_num >= 50 && pin_num <= 55) {
|
||||
// enable GPIOs based on BRD_PWM_COUNT
|
||||
if (pin_num < 50 + pwm_count) {
|
||||
_gpio_tab[i].enabled = false;
|
||||
} else {
|
||||
_gpio_tab[i].enabled = true;
|
||||
}
|
||||
struct gpio_entry *g = &_gpio_tab[i];
|
||||
if (g->pwm_num != 0) {
|
||||
g->enabled = g->pwm_num > pwm_count;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -55,8 +55,8 @@ PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
# PA15 ALARM
|
||||
|
||||
PB0 EXTERN_DRDY INPUT
|
||||
PB1 EXTERN_GPIO INPUT
|
||||
PB0 EXTERN_GPIO1 OUTPUT GPIO(1)
|
||||
PB1 EXTERN_GPIO2 OUTPUT GPIO(2)
|
||||
PB2 BOOT1 INPUT
|
||||
PB3 FMU_SW0 INPUT
|
||||
PB8 I2C1_SCL I2C1
|
||||
@ -102,8 +102,8 @@ PD9 USART3_RX USART3
|
||||
PD10 FRAM_CS CS
|
||||
PD11 USART3_CTS USART3
|
||||
PD12 USART3_RTS USART3
|
||||
PD13 TIM4_CH2 TIM4 PWM5
|
||||
PD14 TIM4_CH3 TIM4 PWM6
|
||||
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
||||
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
||||
PD15 MPU_DRDY INPUT
|
||||
|
||||
# UART8 serial4 GPS2
|
||||
@ -117,12 +117,12 @@ PE6 SPI4_MOSI SPI4
|
||||
# UART7 debug console
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
PE9 TIM1_CH1 TIM1 PWM4
|
||||
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
||||
PE10 VDD_5V_HIPOWER_OC INPUT
|
||||
PE11 TIM1_CH2 TIM1 PWM3
|
||||
PE12 FMU_LED_AMBER OUTPUT
|
||||
PE13 TIM1_CH3 TIM1 PWM2
|
||||
PE14 TIM1_CH4 TIM1 PWM1
|
||||
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
|
||||
PE12 FMU_LED_AMBER OUTPUT GPIO(0)
|
||||
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
|
||||
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
|
||||
PE15 VDD_5V_PERIPH_OC INPUT
|
||||
|
||||
# SPI device table. The DEVID values are chosen to match the PX4 port
|
||||
|
@ -57,10 +57,10 @@ PA14 JTCK-SWCLK SWD
|
||||
|
||||
# PA15 ALARM
|
||||
PB0 TIM3_CH3 TIM3 PPMIN # RC Input PPM
|
||||
PB1 LED_GREEN OUTPUT
|
||||
PB1 LED_GREEN OUTPUT GPIO(0)
|
||||
PB2 BOOT1 INPUT
|
||||
PB3 LED_BLUE OUTPUT
|
||||
PB4 8266_GPIO2 OUTPUT
|
||||
PB3 LED_BLUE OUTPUT GPIO(1)
|
||||
PB4 8266_GPIO2 OUTPUT GPIO(3)
|
||||
PB5 VDD_BRICK_VALID INPUT
|
||||
|
||||
# USART1 is ESP8266
|
||||
@ -71,7 +71,7 @@ PB9 I2C1_SDA I2C1
|
||||
|
||||
# SPI2 is FRAM
|
||||
PB10 SPI2_SCK SPI2
|
||||
PB11 LED_RED OUTPUT
|
||||
PB11 LED_RED OUTPUT GPIO(2)
|
||||
PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
PB14 SPI2_MISO SPI2
|
||||
@ -114,15 +114,15 @@ PD10 FRAM_CS CS
|
||||
PD11 USART3_CTS USART3
|
||||
PD12 USART3_RTS USART3
|
||||
|
||||
PD13 TIM4_CH2 TIM4 PWM5
|
||||
PD14 TIM4_CH3 TIM4 PWM6
|
||||
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
||||
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
||||
|
||||
PD15 MPU9250_DRDY INPUT
|
||||
|
||||
# UART8 serial4 FrSky
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
PE2 8266_GPI0 OUTPUT
|
||||
PE2 8266_GPI0 OUTPUT GPIO(7)
|
||||
PE3 VDD_SENSORS_EN OUTPUT HIGH
|
||||
PE4 SPEKTRUM_PWR OUTPUT HIGH
|
||||
PE5 8266_PD OUTPUT LOW
|
||||
@ -131,12 +131,12 @@ PE6 8266_RST OUTPUT LOW
|
||||
# UART7 is debug
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
PE9 TIM1_CH1 TIM1 PWM4
|
||||
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
||||
PE10 8266_CTS OUTPUT HIGH
|
||||
PE11 TIM1_CH2 TIM1 PWM3
|
||||
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
|
||||
PE12 MAG_DRDY INPUT
|
||||
PE13 TIM1_CH3 TIM1 PWM2
|
||||
PE14 TIM1_CH4 TIM1 PWM1
|
||||
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
|
||||
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
|
||||
PE15 MAG_CS CS
|
||||
|
||||
# SPI device table. The DEVID values are chosen to match the PX4 port
|
||||
|
@ -50,8 +50,8 @@ UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1
|
||||
# UART4 is GPS
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
PA2 TIM2_CH3 TIM2 PWM15
|
||||
PA3 TIM2_CH4 TIM2 PWM16
|
||||
PA2 TIM2_CH3 TIM2 PWM(15)
|
||||
PA3 TIM2_CH4 TIM2 PWM(16)
|
||||
PA4 VDD_5V_SENS ADC1
|
||||
|
||||
# SPI1 is fram bus
|
||||
@ -59,7 +59,7 @@ PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 TONE INPUT
|
||||
|
||||
PA8 RUN_LED OUTPUT
|
||||
PA8 RUN_LED OUTPUT GPIO(0)
|
||||
PA9 VBUS INPUT
|
||||
PA10 SBUS_INV OUTPUT
|
||||
|
||||
@ -69,13 +69,13 @@ PA12 OTG_FS_DP OTG1
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PA15 TIM2_CH1 TIM2 PWM13
|
||||
PA15 TIM2_CH1 TIM2 PWM(13) GPIO(54)
|
||||
|
||||
PB0 TIM3_CH3 TIM3 PWM11
|
||||
PB1 TIM3_CH4 TIM3 PWM12
|
||||
PB0 TIM3_CH3 TIM3 PWM(11) GPIO(52)
|
||||
PB1 TIM3_CH4 TIM3 PWM(12) GPIO(53)
|
||||
PB2 GYRO_CS CS
|
||||
PB3 TIM2_CH2 TIM2 PWM14
|
||||
PB4 TIM3_CH1 TIM3 PWM9
|
||||
PB3 TIM2_CH2 TIM2 PWM(14) GPIO(55)
|
||||
PB4 TIM3_CH1 TIM3 PWM(9) GPIO(50)
|
||||
PB5 SPI1_MOSI SPI1
|
||||
|
||||
# USART1 is SBUS
|
||||
@ -104,7 +104,7 @@ PC3 FMU_ADC1 ADC1
|
||||
PC4 FMU_ADC2 ADC1
|
||||
PC5 FMU_ADC3 ADC1
|
||||
PC6 TIM8_CH1 TIM8 PPMIN # RC PPM input
|
||||
PC7 TIM3_CH2 TIM3 PWM10
|
||||
PC7 TIM3_CH2 TIM3 PWM(10) GPIO(51)
|
||||
|
||||
PC8 SDIO_D0 SDIO
|
||||
PC9 SDIO_D1 SDIO
|
||||
@ -133,10 +133,10 @@ PD9 USART3_RX USART3
|
||||
PD10 NRF_INT INPUT
|
||||
PD11 ACCEL_MAG_CS CS
|
||||
|
||||
PD12 TIM4_CH1 TIM4 PWM5
|
||||
PD13 TIM4_CH2 TIM4 PWM6
|
||||
PD14 TIM4_CH3 TIM4 PWM7
|
||||
PD15 TIM4_CH4 TIM4 PWM8
|
||||
PD12 TIM4_CH1 TIM4 PWM(5)
|
||||
PD13 TIM4_CH2 TIM4 PWM(6)
|
||||
PD14 TIM4_CH3 TIM4 PWM(7)
|
||||
PD15 TIM4_CH4 TIM4 PWM(8)
|
||||
|
||||
# UART8 is FrSky
|
||||
PE0 UART8_RX UART8
|
||||
@ -153,12 +153,12 @@ PE6 SPI4_MOSI SPI4
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
|
||||
PE9 TIM1_CH1 TIM1 PWM1
|
||||
PE9 TIM1_CH1 TIM1 PWM(1)
|
||||
PE10 MPU_DRDY INPUT
|
||||
PE11 TIM1_CH2 TIM1 PWM2
|
||||
PE11 TIM1_CH2 TIM1 PWM(2)
|
||||
PE12 FRAM_CS CS
|
||||
PE13 TIM1_CH3 TIM1 PWM3
|
||||
PE14 TIM1_CH4 TIM1 PWM4
|
||||
PE13 TIM1_CH3 TIM1 PWM(3)
|
||||
PE14 TIM1_CH4 TIM1 PWM(4)
|
||||
PE15 NRF_CS CS
|
||||
|
||||
# SPI device table
|
||||
|
@ -225,8 +225,8 @@ class generic_pin(object):
|
||||
str += " AF%u" % self.af
|
||||
if self.type.startswith('ADC1'):
|
||||
str += " ADC1_IN%u" % get_ADC1_chan(mcu_type, self.portpin)
|
||||
if self.extra_prefix('PWM'):
|
||||
str += " %s" % self.extra_prefix('PWM')
|
||||
if self.extra_value('PWM', type=int):
|
||||
str += " PWM%u" % self.extra_value('PWM', type=int)
|
||||
return "P%s%u %s %s%s" % (self.port, self.pin, self.label, self.type, str)
|
||||
|
||||
# setup default as input pins
|
||||
@ -507,7 +507,7 @@ def write_PWM_config(f):
|
||||
if p.has_extra('PPMIN'):
|
||||
ppm_in = p
|
||||
else:
|
||||
if p.extra_prefix('PWM') is not None:
|
||||
if p.extra_value('PWM', type=int) is not None:
|
||||
pwm_out.append(p)
|
||||
if p.type not in pwm_timers:
|
||||
pwm_timers.append(p.type)
|
||||
@ -542,12 +542,8 @@ def write_PWM_config(f):
|
||||
chan = int(chan_str)
|
||||
if chan not in [1,2,3,4]:
|
||||
error("Bad channel number %u for PWM %s" % (chan, p))
|
||||
pwm = p.extra_prefix('PWM')
|
||||
pwmchan_str = pwm[3:]
|
||||
if not is_int(pwmchan_str):
|
||||
errors("Bad PWM number in %s" % p)
|
||||
pwmchan = int(pwmchan_str)
|
||||
chan_list[chan-1] = pwmchan-1
|
||||
pwm = p.extra_value('PWM', type=int)
|
||||
chan_list[chan-1] = pwm-1
|
||||
chan_mode[chan-1] = 'PWM_OUTPUT_ACTIVE_HIGH'
|
||||
groups.append('HAL_PWM_GROUP%u' % group)
|
||||
if n in [1, 8]:
|
||||
@ -606,6 +602,35 @@ def write_ADC_config(f):
|
||||
f.write('}\n\n')
|
||||
|
||||
|
||||
def write_GPIO_config(f):
|
||||
'''write GPIO config defines'''
|
||||
f.write('// GPIO config\n')
|
||||
gpios = []
|
||||
for l in bylabel:
|
||||
p = bylabel[l]
|
||||
gpio = p.extra_value('GPIO', type=int)
|
||||
if gpio is None:
|
||||
continue
|
||||
# see if it is also a PWM pin
|
||||
pwm = p.extra_value('PWM', type=int, default=0)
|
||||
port = p.port
|
||||
pin = p.pin
|
||||
gpios.append((gpio, pwm, port, pin, p))
|
||||
gpios = sorted(gpios)
|
||||
f.write('#define HAL_GPIO_PINS { \\\n')
|
||||
for (gpio, pwm, port, pin, p) in gpios:
|
||||
f.write('{ %3u, true, %2u, PAL_LINE(GPIO%s, %2uU) }, /* %s */ \\\n' % (gpio, pwm, port, pin, p))
|
||||
# and write #defines for use by config code
|
||||
f.write('}\n\n')
|
||||
f.write('// full pin define list\n')
|
||||
for l in bylabel:
|
||||
p = bylabel[l]
|
||||
label = p.label
|
||||
label = label.replace('-','_')
|
||||
f.write('#define HAL_GPIO_PIN_%-20s PAL_LINE(GPIO%s,%uU)\n' % (label, p.port, p.pin))
|
||||
f.write('\n')
|
||||
|
||||
|
||||
def write_prototype_file():
|
||||
'''write the prototype file for apj generation'''
|
||||
pf = open(os.path.join(outdir, "apj.prototype"), "w")
|
||||
@ -656,6 +681,7 @@ def write_hwdef_header(outfilename):
|
||||
write_SPI_config(f)
|
||||
write_PWM_config(f)
|
||||
write_ADC_config(f)
|
||||
write_GPIO_config(f)
|
||||
|
||||
write_peripheral_enable(f)
|
||||
write_prototype_file()
|
||||
|
Loading…
Reference in New Issue
Block a user