mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_Linux: add export gpio during direction set if not exported during initialisation
This commit is contained in:
parent
a7ead42f52
commit
85d10e2ce3
@ -60,14 +60,27 @@ void LinuxGPIO::init()
|
||||
|
||||
void LinuxGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
{
|
||||
int fd;
|
||||
int fd,len;
|
||||
char buf[64];
|
||||
|
||||
snprintf(buf, sizeof(buf), SYSFS_GPIO_DIR "/gpio%d/direction", pin);
|
||||
|
||||
fd = ::open(buf, O_WRONLY);
|
||||
if (fd < 0) {
|
||||
perror("LinuxGPIO::direction");
|
||||
fd = open(SYSFS_GPIO_DIR "/export", O_WRONLY); //try exporting GPIO pin
|
||||
if (fd < 0) {
|
||||
perror("LinuxGPIO::direction");
|
||||
}
|
||||
|
||||
len = snprintf(buf, sizeof(buf), "%d", pin);
|
||||
::write(fd, buf, len);
|
||||
close(fd);
|
||||
|
||||
snprintf(buf, sizeof(buf), SYSFS_GPIO_DIR "/gpio%d/direction", pin); //retry writing direction
|
||||
fd = ::open(buf, O_WRONLY);
|
||||
if (fd < 0) {
|
||||
perror("LinuxGPIO::direction"); //report faillure
|
||||
}
|
||||
}
|
||||
|
||||
if (output == GPIO_OUTPUT)
|
||||
|
Loading…
Reference in New Issue
Block a user