HAL_PX4: prevent error on GPIO line on change of pinMode

thanks to Michael for noticing this
This commit is contained in:
Andrew Tridgell 2015-08-17 12:02:03 +10:00 committed by Randy Mackay
parent f7b5c770ac
commit 3990332745

View File

@ -69,7 +69,17 @@ void PX4GPIO::pinMode(uint8_t pin, uint8_t output)
{ {
switch (pin) { switch (pin) {
case PX4_GPIO_FMU_SERVO_PIN(0) ... PX4_GPIO_FMU_SERVO_PIN(5): case PX4_GPIO_FMU_SERVO_PIN(0) ... PX4_GPIO_FMU_SERVO_PIN(5):
ioctl(_gpio_fmu_fd, output?GPIO_SET_OUTPUT:GPIO_SET_INPUT, 1U<<(pin-PX4_GPIO_FMU_SERVO_PIN(0))); uint32_t pinmask = 1U<<(pin-PX4_GPIO_FMU_SERVO_PIN(0));
if (output) {
uint8_t old_value = read(pin);
if (old_value) {
ioctl(_gpio_fmu_fd, GPIO_SET_OUTPUT_HIGH, pinmask);
} else {
ioctl(_gpio_fmu_fd, GPIO_SET_OUTPUT_LOW, pinmask);
}
} else {
ioctl(_gpio_fmu_fd, GPIO_SET_INPUT, pinmask);
}
break; break;
} }
} }