mirror of https://github.com/ArduPilot/ardupilot
HAL_Linux: fix types, remove printfs in GPIO_RPI
This commit is contained in:
parent
6f993fe64a
commit
49d3035ee5
|
@ -23,8 +23,7 @@ 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);
|
||||
hal.scheduler->panic("Can't open /dev/mem");
|
||||
}
|
||||
|
||||
// mmap GPIO
|
||||
|
@ -40,11 +39,10 @@ void LinuxGPIO_RPI::init()
|
|||
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);
|
||||
hal.scheduler->panic("Can't open /dev/mem");
|
||||
}
|
||||
|
||||
gpio = (volatile unsigned *)gpio_map; // Always use volatile pointer!
|
||||
gpio = (volatile uint32_t *)gpio_map; // Always use volatile pointer!
|
||||
}
|
||||
|
||||
void LinuxGPIO_RPI::pinMode(uint8_t pin, uint8_t output)
|
||||
|
|
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue