2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-09-18 10:35:22 -03:00
|
|
|
|
2017-11-02 10:45:18 -03:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
|
2016-01-05 06:28:27 -04:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
|
2016-10-17 15:02:48 -03:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
|
2016-01-05 06:28:27 -04:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
|
2014-09-18 10:35:22 -03:00
|
|
|
|
|
|
|
#include <errno.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <poll.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <stdio.h>
|
|
|
|
#include <stdlib.h>
|
|
|
|
#include <string.h>
|
2014-09-18 10:35:22 -03:00
|
|
|
#include <sys/mman.h>
|
|
|
|
#include <sys/stat.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <unistd.h>
|
2014-09-18 10:35:22 -03:00
|
|
|
|
2016-05-17 23:26:57 -03:00
|
|
|
#include "GPIO.h"
|
|
|
|
#include "Util_RPI.h"
|
2015-03-28 10:46:08 -03:00
|
|
|
|
2016-06-20 11:10:59 -03:00
|
|
|
// Raspberry Pi GPIO memory
|
|
|
|
#define BCM2708_PERI_BASE 0x20000000
|
|
|
|
#define BCM2709_PERI_BASE 0x3F000000
|
|
|
|
#define GPIO_BASE(address) (address + 0x200000)
|
|
|
|
|
|
|
|
// GPIO setup. Always use INP_GPIO(x) before OUT_GPIO(x) or SET_GPIO_ALT(x,y)
|
|
|
|
#define GPIO_MODE_IN(g) *(_gpio+((g)/10)) &= ~(7<<(((g)%10)*3))
|
|
|
|
#define GPIO_MODE_OUT(g) *(_gpio+((g)/10)) |= (1<<(((g)%10)*3))
|
|
|
|
#define GPIO_MODE_ALT(g,a) *(_gpio+(((g)/10))) |= (((a)<=3?(a)+4:(a)==4?3:2)<<(((g)%10)*3))
|
|
|
|
#define GPIO_SET_HIGH *(_gpio+7) // sets bits which are 1
|
|
|
|
#define GPIO_SET_LOW *(_gpio+10) // clears bits which are 1
|
|
|
|
#define GPIO_GET(g) (*(_gpio+13)&(1<<g)) // 0 if LOW, (1<<g) if HIGH
|
2018-07-10 22:28:49 -03:00
|
|
|
#define GPIO_RPI_MAX_NUMBER_PINS 32
|
2016-06-20 11:10:59 -03:00
|
|
|
|
2014-09-18 10:35:22 -03:00
|
|
|
using namespace Linux;
|
|
|
|
|
2016-06-20 11:10:59 -03:00
|
|
|
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
GPIO_RPI::GPIO_RPI()
|
2016-06-20 11:10:59 -03:00
|
|
|
{
|
|
|
|
}
|
2014-09-18 10:35:22 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void GPIO_RPI::init()
|
2014-09-18 10:35:22 -03:00
|
|
|
{
|
2015-10-20 18:13:25 -03:00
|
|
|
int rpi_version = UtilRPI::from(hal.util)->get_rpi_version();
|
2015-09-23 12:52:07 -03:00
|
|
|
uint32_t gpio_address = rpi_version == 1 ? GPIO_BASE(BCM2708_PERI_BASE) : GPIO_BASE(BCM2709_PERI_BASE);
|
2016-06-20 11:10:59 -03:00
|
|
|
|
2016-10-30 10:22:29 -03:00
|
|
|
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
|
2016-06-20 11:10:59 -03:00
|
|
|
if (mem_fd < 0) {
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Can't open /dev/mem");
|
2014-11-05 09:56:12 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// mmap GPIO
|
2016-06-20 11:10:59 -03:00
|
|
|
void *gpio_map = mmap(
|
2016-10-30 02:24:21 -03:00
|
|
|
nullptr, // Any adddress in our space will do
|
2014-11-05 09:56:12 -04:00
|
|
|
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
|
2015-09-23 12:52:07 -03:00
|
|
|
gpio_address // Offset to GPIO peripheral
|
2015-08-17 23:32:29 -03:00
|
|
|
);
|
|
|
|
|
2014-11-05 09:56:12 -04:00
|
|
|
close(mem_fd); // No need to keep mem_fd open after mmap
|
|
|
|
|
2016-06-20 10:46:47 -03:00
|
|
|
if (gpio_map == MAP_FAILED) {
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Can't open /dev/mem");
|
2014-11-05 09:56:12 -04:00
|
|
|
}
|
|
|
|
|
2016-06-20 11:10:59 -03:00
|
|
|
_gpio = (volatile uint32_t *)gpio_map;
|
2014-09-18 10:35:22 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void GPIO_RPI::pinMode(uint8_t pin, uint8_t output)
|
2014-09-18 10:35:22 -03:00
|
|
|
{
|
|
|
|
if (output == HAL_GPIO_INPUT) {
|
|
|
|
GPIO_MODE_IN(pin);
|
|
|
|
} else {
|
|
|
|
GPIO_MODE_IN(pin);
|
|
|
|
GPIO_MODE_OUT(pin);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
|
2015-08-17 23:32:29 -03:00
|
|
|
{
|
|
|
|
if (output == HAL_GPIO_INPUT) {
|
|
|
|
GPIO_MODE_IN(pin);
|
|
|
|
} else if (output == HAL_GPIO_ALT) {
|
|
|
|
GPIO_MODE_IN(pin);
|
|
|
|
GPIO_MODE_ALT(pin, alt);
|
|
|
|
} else {
|
|
|
|
GPIO_MODE_IN(pin);
|
|
|
|
GPIO_MODE_OUT(pin);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
uint8_t GPIO_RPI::read(uint8_t pin)
|
2014-09-18 10:35:22 -03:00
|
|
|
{
|
2018-07-10 22:28:49 -03:00
|
|
|
if (pin >= GPIO_RPI_MAX_NUMBER_PINS) {
|
|
|
|
return 0;
|
|
|
|
}
|
2014-11-06 10:01:03 -04:00
|
|
|
uint32_t value = GPIO_GET(pin);
|
|
|
|
return value ? 1: 0;
|
2014-09-18 10:35:22 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void GPIO_RPI::write(uint8_t pin, uint8_t value)
|
2014-09-18 10:35:22 -03:00
|
|
|
{
|
|
|
|
if (value == LOW) {
|
|
|
|
GPIO_SET_LOW = 1 << pin;
|
|
|
|
} else {
|
|
|
|
GPIO_SET_HIGH = 1 << pin;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void GPIO_RPI::toggle(uint8_t pin)
|
2014-09-18 10:35:22 -03:00
|
|
|
{
|
|
|
|
write(pin, !read(pin));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Alternative interface: */
|
2016-06-20 11:10:59 -03:00
|
|
|
AP_HAL::DigitalSource* GPIO_RPI::channel(uint16_t n)
|
|
|
|
{
|
2015-10-20 18:13:25 -03:00
|
|
|
return new DigitalSource(n);
|
2014-09-18 10:35:22 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/* Interrupt interface: */
|
2015-10-20 18:13:25 -03:00
|
|
|
bool GPIO_RPI::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
|
2014-09-18 10:35:22 -03:00
|
|
|
{
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
bool GPIO_RPI::usb_connected(void)
|
2014-09-18 10:35:22 -03:00
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-01-05 13:33:45 -04:00
|
|
|
#endif
|