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