mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
HAL_Linux: Remove panic when invalid pin in GPIO
When a invalid pin is passed as a parameter the methods return without performing anything insted of raising a panic.
This commit is contained in:
parent
245618e298
commit
95e0803880
@ -63,7 +63,6 @@ void LinuxGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
uint8_t bank = pin/32;
|
||||
uint8_t bankpin = pin & 0x1F;
|
||||
if (bank >= LINUX_GPIO_NUM_BANKS) {
|
||||
hal.scheduler->panic("invalid pin number");
|
||||
return;
|
||||
}
|
||||
if (output == HAL_GPIO_INPUT) {
|
||||
@ -83,7 +82,6 @@ uint8_t LinuxGPIO::read(uint8_t pin) {
|
||||
uint8_t bank = pin/32;
|
||||
uint8_t bankpin = pin & 0x1F;
|
||||
if (bank >= LINUX_GPIO_NUM_BANKS) {
|
||||
hal.scheduler->panic("invalid pin number");
|
||||
return 0;
|
||||
}
|
||||
return *gpio_bank[bank].in & (1U<<bankpin) ? HIGH : LOW;
|
||||
@ -95,7 +93,6 @@ void LinuxGPIO::write(uint8_t pin, uint8_t value)
|
||||
uint8_t bank = pin/32;
|
||||
uint8_t bankpin = pin & 0x1F;
|
||||
if (bank >= LINUX_GPIO_NUM_BANKS) {
|
||||
hal.scheduler->panic("invalid pin number");
|
||||
return;
|
||||
}
|
||||
if (value == LOW) {
|
||||
|
Loading…
Reference in New Issue
Block a user