diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.cpp b/libraries/AP_HAL_Linux/GPIO_RPI.cpp index 3b3ff4287f19428eda734554fd67e96d16dbfab7..6c89e6a513bf2c1c3bc5cc6c7ab9227916f267c2 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.cpp +++ b/libraries/AP_HAL_Linux/GPIO_RPI.cpp @@ -22,29 +22,27 @@ LinuxGPIO_RPI::LinuxGPIO_RPI() void LinuxGPIO_RPI::init() { // 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 - gpio_map = mmap( - NULL, // Any adddress in our space will do - BLOCK_SIZE, // Map length - PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory - MAP_SHARED, // Shared with other processes - mem_fd, // File to map - GPIO_BASE // Offset to GPIO peripheral - ); - - close(mem_fd); // No need to keep mem_fd open after mmap - - if (gpio_map == MAP_FAILED) { - printf("mmap error %d\n", (int)gpio_map); // errno also set! - exit(-1); - } - - gpio = (volatile unsigned *)gpio_map; // Always use volatile pointer! + if ((mem_fd = open("/dev/mem", O_RDWR|O_SYNC) ) < 0) { + hal.scheduler->panic("Can't open /dev/mem"); + } + + // mmap GPIO + gpio_map = mmap( + NULL, // Any adddress in our space will do + BLOCK_SIZE, // Map length + PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory + MAP_SHARED, // Shared with other processes + mem_fd, // File to map + GPIO_BASE // Offset to GPIO peripheral + ); + + close(mem_fd); // No need to keep mem_fd open after mmap + + if (gpio_map == MAP_FAILED) { + hal.scheduler->panic("Can't open /dev/mem"); + } + + gpio = (volatile uint32_t *)gpio_map; // Always use volatile pointer! } void LinuxGPIO_RPI::pinMode(uint8_t pin, uint8_t output) diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.h b/libraries/AP_HAL_Linux/GPIO_RPI.h index b8724400fccadd66c668d216d3d0394b11ea5f7b..06409366994d6d14428b4749cc7bad9317471f2a 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.h +++ b/libraries/AP_HAL_Linux/GPIO_RPI.h @@ -2,6 +2,7 @@ #ifndef __AP_HAL_LINUX_GPIO_RPI_H__ #define __AP_HAL_LINUX_GPIO_RPI_H__ +#include <stdint.h> #include <AP_HAL_Linux.h> #define LOW 0 @@ -48,7 +49,7 @@ class Linux::LinuxGPIO_RPI : public AP_HAL::GPIO { private: int mem_fd; void *gpio_map; - volatile unsigned *gpio; + volatile uint32_t *gpio; public: LinuxGPIO_RPI();