HAL_ChibiOS: support building with no GPIOs

This commit is contained in:
Andrew Tridgell 2024-01-17 14:37:01 +11:00
parent b8e14c166f
commit 3a84f35593
2 changed files with 33 additions and 9 deletions

View File

@ -37,9 +37,8 @@ using namespace ChibiOS;
extern AP_IOMCU iomcu;
#endif
// GPIO pin table from hwdef.dat
static struct gpio_entry {
struct gpio_entry {
uint8_t pin_num;
bool enabled;
uint8_t pwm_num;
@ -51,13 +50,22 @@ static struct gpio_entry {
uint16_t isr_quota;
uint8_t isr_disabled_ticks;
AP_HAL::GPIO::INTERRUPT_TRIGGER_TYPE isr_mode;
} _gpio_tab[] = HAL_GPIO_PINS;
};
#ifdef HAL_GPIO_PINS
#define HAVE_GPIO_PINS 1
static struct gpio_entry _gpio_tab[] = HAL_GPIO_PINS;
#else
#define HAVE_GPIO_PINS 0
#endif
/*
map a user pin number to a GPIO table entry
*/
static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num, bool check_enabled=true)
{
#if HAVE_GPIO_PINS
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
const auto &t = _gpio_tab[i];
if (pin_num == t.pin_num) {
@ -67,6 +75,7 @@ static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num, bool check_enabled=tr
return &_gpio_tab[i];
}
}
#endif
return NULL;
}
@ -79,7 +88,9 @@ GPIO::GPIO()
void GPIO::init()
{
#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) && !defined(HAL_BOOTLOADER_BUILD)
#if HAL_WITH_IO_MCU || HAVE_GPIO_PINS
uint8_t chan_offset = 0;
#endif
#if HAL_WITH_IO_MCU
if (AP_BoardConfig::io_enabled()) {
uint8_t GPIO_mask = 0;
@ -93,12 +104,14 @@ void GPIO::init()
}
#endif
// auto-disable pins being used for PWM output
#if HAVE_GPIO_PINS
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
struct gpio_entry *g = &_gpio_tab[i];
if (g->pwm_num != 0) {
g->enabled = SRV_Channels::is_GPIO((g->pwm_num-1)+chan_offset);
}
}
#endif // HAVE_GPIO_PINS
#endif // HAL_BOOTLOADER_BUILD
#ifdef HAL_PIN_ALT_CONFIG
setup_alt_config();
@ -139,6 +152,7 @@ void GPIO::setup_alt_config(void)
if (alt_config == alt.alternate) {
if (alt.periph_type == PERIPH_TYPE::GPIO) {
// enable pin in GPIO table
#if HAVE_GPIO_PINS
for (uint8_t j=0; j<ARRAY_SIZE(_gpio_tab); j++) {
struct gpio_entry *g = &_gpio_tab[j];
if (g->pal_line == alt.line) {
@ -146,6 +160,7 @@ void GPIO::setup_alt_config(void)
break;
}
}
#endif // HAVE_GPIO_PINS
continue;
}
const iomode_t mode = alt.mode & ~PAL_STM32_HIGH;
@ -523,7 +538,9 @@ bool GPIO::valid_pin(uint8_t pin) const
// servo_ch uses zero-based indexing
bool GPIO::pin_to_servo_channel(uint8_t pin, uint8_t& servo_ch) const
{
#if HAL_WITH_IO_MCU || HAVE_GPIO_PINS
uint8_t fmu_chan_offset = 0;
#endif
#if HAL_WITH_IO_MCU
if (AP_BoardConfig::io_enabled()) {
// check if this is one of the main pins
@ -537,6 +554,7 @@ bool GPIO::pin_to_servo_channel(uint8_t pin, uint8_t& servo_ch) const
}
#endif
#if HAVE_GPIO_PINS
// search _gpio_tab for matching pin
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
if (_gpio_tab[i].pin_num == pin) {
@ -547,6 +565,7 @@ bool GPIO::pin_to_servo_channel(uint8_t pin, uint8_t& servo_ch) const
return true;
}
}
#endif // HAVE_GPIO_PINS
return false;
}
@ -581,6 +600,7 @@ void GPIO::timer_tick()
{
// allow 100k interrupts/second max for GPIO interrupt sources, which is
// 10k per 100ms call to timer_tick()
#if HAVE_GPIO_PINS
const uint16_t quota = 10000U;
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
if (_gpio_tab[i].isr_quota != 1) {
@ -628,17 +648,20 @@ void GPIO::timer_tick()
}
}
}
#endif // HAVE_GPIO_PINS
}
// Check for ISR floods
bool GPIO::arming_checks(size_t buflen, char *buffer) const
{
#if HAVE_GPIO_PINS
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
if (_gpio_tab[i].isr_disabled_ticks != 0) {
hal.util->snprintf(buffer, buflen, "Pin %u disabled (ISR flood)", _gpio_tab[i].pin_num);
return false;
}
}
#endif // HAVE_GPIO_PINS
return true;
}
#endif // IOMCU_FW

View File

@ -2383,12 +2383,13 @@ INCLUDE common.ld
gpios = sorted(gpios)
for (gpio, pwm, port, pin, p, enabled) in gpios:
f.write('#define HAL_GPIO_LINE_GPIO%u PAL_LINE(GPIO%s,%uU)\n' % (gpio, port, pin))
f.write('#define HAL_GPIO_PINS { \\\n')
for (gpio, pwm, port, pin, p, enabled) in gpios:
f.write('{ %3u, %s, %2u, PAL_LINE(GPIO%s,%uU)}, /* %s */ \\\n' %
(gpio, enabled, pwm, port, pin, p))
# and write #defines for use by config code
f.write('}\n\n')
if len(gpios) > 0:
f.write('#define HAL_GPIO_PINS { \\\n')
for (gpio, pwm, port, pin, p, enabled) in gpios:
f.write('{ %3u, %s, %2u, PAL_LINE(GPIO%s,%uU)}, /* %s */ \\\n' %
(gpio, enabled, pwm, port, pin, p))
# and write #defines for use by config code
f.write('}\n\n')
f.write('// full pin define list\n')
last_label = None
for label in sorted(list(set(self.bylabel.keys()))):