#include #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include "GPIO.h" #include #include #include #include #include #include #include #include #include using namespace Linux; static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; LinuxGPIO::LinuxGPIO() {} void LinuxGPIO::init() { #if LINUX_GPIO_NUM_BANKS == 4 int mem_fd; // Enable all GPIO banks // Without this, access to deactivated banks (i.e. those with no clock source set up) will (logically) fail with SIGBUS // Idea taken from https://groups.google.com/forum/#!msg/beagleboard/OYFp4EXawiI/Mq6s3sg14HoJ uint8_t bank_enable[3] = { 5, 65, 105 }; int export_fd = open("/sys/class/gpio/export", O_WRONLY); if (export_fd == -1) { hal.scheduler->panic("unable to open /sys/class/gpio/export"); } for (uint8_t i=0; i<3; i++) { dprintf(export_fd, "%u\n", (unsigned)bank_enable[i]); } close(export_fd); /* open /dev/mem */ if ((mem_fd = open("/dev/mem", O_RDWR|O_SYNC) ) < 0) { printf("can't open /dev/mem \n"); exit (-1); } /* mmap GPIO */ off_t offsets[LINUX_GPIO_NUM_BANKS] = { GPIO0_BASE, GPIO1_BASE, GPIO2_BASE, GPIO3_BASE }; for (uint8_t i=0; ipanic("unable to map GPIO bank"); } gpio_bank[i].oe = gpio_bank[i].base + GPIO_OE; gpio_bank[i].in = gpio_bank[i].base + GPIO_IN; gpio_bank[i].out = gpio_bank[i].base + GPIO_OUT; } close(mem_fd); #endif // LINUX_GPIO_NUM_BANKS } 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) { return; } if (output == HAL_GPIO_INPUT) { *gpio_bank[bank].oe |= (1U<= LINUX_GPIO_NUM_BANKS) { return 0; } return *gpio_bank[bank].in & (1U<= LINUX_GPIO_NUM_BANKS) { return; } if (value == LOW) { *gpio_bank[bank].out &= ~(1U<pinMode(_v, output); } uint8_t LinuxDigitalSource::read() { return hal.gpio->read(_v); } void LinuxDigitalSource::write(uint8_t value) { return hal.gpio->write(_v,value); } void LinuxDigitalSource::toggle() { write(!read()); } #endif // CONFIG_HAL_BOARD