mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_LINUX:toggle gpio port
This commit is contained in:
parent
d95f6c8c2f
commit
280788bfdf
@ -228,7 +228,12 @@ void GPIO_RPI::write(uint8_t pin, uint8_t value)
|
|||||||
|
|
||||||
void GPIO_RPI::toggle(uint8_t pin)
|
void GPIO_RPI::toggle(uint8_t pin)
|
||||||
{
|
{
|
||||||
write(pin, !read(pin));
|
if (pin >= GPIO_RPI_MAX_NUMBER_PINS) {
|
||||||
|
return ;
|
||||||
|
}
|
||||||
|
uint32_t flag = (1 << pin);
|
||||||
|
_gpio_output_port_status ^= flag;
|
||||||
|
write(pin, (_gpio_output_port_status & flag) >> pin);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Alternative interface: */
|
/* Alternative interface: */
|
||||||
|
@ -192,6 +192,9 @@ private:
|
|||||||
// File descriptor for the memory device file
|
// File descriptor for the memory device file
|
||||||
// If it's negative, then there was an error opening the file.
|
// If it's negative, then there was an error opening the file.
|
||||||
int _system_memory_device;
|
int _system_memory_device;
|
||||||
|
// store GPIO output status.
|
||||||
|
uint32_t _gpio_output_port_status = 0x00;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user