HAL_ChibiOS: implement valid_pin()

This commit is contained in:
Andrew Tridgell 2021-07-20 14:19:40 +10:00
parent 4dcff3d900
commit d302d3c90a
2 changed files with 9 additions and 0 deletions

View File

@ -440,6 +440,12 @@ bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_u
return msg == MSG_OK; return msg == MSG_OK;
} }
// check if a pin number is valid
bool GPIO::valid_pin(uint8_t pin) const
{
return gpio_by_pin_num(pin) != nullptr;
}
#ifndef IOMCU_FW #ifndef IOMCU_FW
/* /*
timer to setup interrupt quotas for a 100ms period from timer to setup interrupt quotas for a 100ms period from

View File

@ -78,6 +78,9 @@ public:
void timer_tick(void) override; void timer_tick(void) override;
#endif #endif
// check if a pin number is valid
bool valid_pin(uint8_t pin) const override;
/* /*
resolve an ioline to take account of alternative configurations resolve an ioline to take account of alternative configurations
*/ */