mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_IOMCU: valid_GPIO_pin checks if pin configured for GPIO
This commit is contained in:
parent
892cea622f
commit
79e73e1683
@ -1064,10 +1064,16 @@ void AP_IOMCU::check_iomcu_reset(void)
|
|||||||
last_rc_protocols = 0;
|
last_rc_protocols = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check if pin number is valid for GPIO
|
// Check if pin number is valid and configured for GPIO
|
||||||
bool AP_IOMCU::valid_GPIO_pin(uint8_t pin) const
|
bool AP_IOMCU::valid_GPIO_pin(uint8_t pin) const
|
||||||
{
|
{
|
||||||
return convert_pin_number(pin);
|
// sanity check pin number
|
||||||
|
if (!convert_pin_number(pin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// check pin is enabled as GPIO
|
||||||
|
return ((GPIO.channel_mask & (1U << pin)) != 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// convert external pin numbers 101 to 108 to internal 0 to 7
|
// convert external pin numbers 101 to 108 to internal 0 to 7
|
||||||
|
@ -107,7 +107,7 @@ public:
|
|||||||
bool setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
bool setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
||||||
float mixing_gain, uint16_t manual_rc_mask);
|
float mixing_gain, uint16_t manual_rc_mask);
|
||||||
|
|
||||||
// Check if pin number is valid for GPIO
|
// Check if pin number is valid and configured for GPIO
|
||||||
bool valid_GPIO_pin(uint8_t pin) const;
|
bool valid_GPIO_pin(uint8_t pin) const;
|
||||||
|
|
||||||
// convert external pin numbers 101 to 108 to internal 0 to 7
|
// convert external pin numbers 101 to 108 to internal 0 to 7
|
||||||
|
Loading…
Reference in New Issue
Block a user