Browse Source

HAL_Linux: make GPIO code compact and readable

add hal instance to generate scheduler
change gpio/export write method
add gpio struct to LinuxDigitalSource class
change individual gpio banks to one gpio_bank array
mission-4.1.18
bugobliterator 11 years ago committed by Andrew Tridgell
parent
commit
1f1af0b0ea
  1. 255
      libraries/AP_HAL_Linux/GPIO.cpp
  2. 12
      libraries/AP_HAL_Linux/GPIO.h

255
libraries/AP_HAL_Linux/GPIO.cpp

@ -15,15 +15,7 @@
using namespace Linux; using namespace Linux;
struct GPIO{ static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
volatile unsigned *base;
volatile unsigned *oe;
volatile unsigned *in;
volatile unsigned *out;
}gpio0,gpio1,gpio2,gpio3;
LinuxGPIO::LinuxGPIO() LinuxGPIO::LinuxGPIO()
{} {}
@ -33,9 +25,17 @@ void LinuxGPIO::init()
// Enable all GPIO banks // Enable all GPIO banks
// Without this, access to deactivated banks (i.e. those with no clock source set up) will (logically) fail with SIGBUS // 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 // Idea taken from https://groups.google.com/forum/#!msg/beagleboard/OYFp4EXawiI/Mq6s3sg14HoJ
system("echo 5 > /sys/class/gpio/export");
system("echo 65 > /sys/class/gpio/export"); uint8_t bank_enable[3] = { 5, 65, 105 };
system("echo 105 > /sys/class/gpio/export"); 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 */ /* 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) {
@ -44,78 +44,34 @@ void LinuxGPIO::init()
} }
/* mmap GPIO */ /* mmap GPIO */
gpio0.base = (volatile unsigned *)mmap(0, GPIO_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, GPIO0_BASE); off_t offsets[LINUX_GPIO_NUM_BANKS] = { GPIO0_BASE, GPIO1_BASE, GPIO2_BASE, GPIO3_BASE };
if ((char *)gpio0.base == MAP_FAILED) { for (uint8_t i=0; i<LINUX_GPIO_NUM_BANKS; i++) {
printf("mmap error %d\n", (int)gpio0.base); gpio_bank[i].base = (volatile unsigned *)mmap(0, GPIO_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, offsets[i]);
exit (-1); if ((char *)gpio_bank[i].base == MAP_FAILED) {
} hal.scheduler->panic("unable to map GPIO bank");
gpio1.base = (volatile unsigned *)mmap(0, GPIO_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, GPIO1_BASE); }
if ((char *)gpio1.base == MAP_FAILED) { gpio_bank[i].oe = gpio_bank[i].base + GPIO_OE;
printf("mmap error %d\n", (int)gpio1.base); gpio_bank[i].in = gpio_bank[i].base + GPIO_IN;
exit (-1); gpio_bank[i].out = gpio_bank[i].base + GPIO_OUT;
}
gpio2.base = (volatile unsigned *)mmap(0, GPIO_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, GPIO2_BASE);
if ((char *)gpio2.base == MAP_FAILED) {
printf("mmap error %d\n", (int)gpio2.base);
exit (-1);
}
gpio3.base = (volatile unsigned *)mmap(0, GPIO_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, GPIO3_BASE);
if ((char *)gpio3.base == MAP_FAILED) {
printf("mmap error %d\n", (int)gpio3.base);
exit (-1);
} }
gpio0.oe = gpio0.base + GPIO_OE;
gpio0.in = gpio0.base + GPIO_IN;
gpio0.out = gpio0.base + GPIO_OUT;
gpio1.oe = gpio1.base + GPIO_OE;
gpio1.in = gpio1.base + GPIO_IN;
gpio1.out = gpio1.base + GPIO_OUT;
gpio2.oe = gpio2.base + GPIO_OE;
gpio2.in = gpio2.base + GPIO_IN;
gpio2.out = gpio2.base + GPIO_OUT;
gpio3.oe = gpio3.base + GPIO_OE;
gpio3.in = gpio3.base + GPIO_IN;
gpio3.out = gpio3.base + GPIO_OUT;
close(mem_fd); close(mem_fd);
} }
void LinuxGPIO::pinMode(uint8_t pin, uint8_t output) void LinuxGPIO::pinMode(uint8_t pin, uint8_t output)
{ {
if(output == GPIO_INPUT){ uint8_t bank = pin/32;
if(pin/32 < 1){ uint8_t bankpin = pin & 0x1F;
*gpio0.oe = *gpio0.oe | (1<<pin); if (bank >= LINUX_GPIO_NUM_BANKS) {
} hal.scheduler->panic("invalid pin number");
else if(pin/32 < 2){ return;
*gpio1.oe = *gpio1.oe | (1<<(pin-32));
}
else if(pin/32 < 3){
*gpio2.oe = *gpio2.oe | (1<<(pin-64));
}
else if(pin/32 < 4){
*gpio3.oe = *gpio3.oe | (1<<(pin-96));
}
} }
else{ if (output == GPIO_INPUT) {
if(pin/32 < 1){ *gpio_bank[bank].oe |= (1U<<bankpin);
*gpio0.oe = *gpio0.oe & (~(1<<pin)); } else {
} *gpio_bank[bank].oe &= ~(1U<<bankpin);
else if(pin/32 < 2){
*gpio1.oe = *gpio1.oe & (~(1<<(pin-32)));
}
else if(pin/32 < 3){
*gpio2.oe = *gpio2.oe & (~(1<<(pin-64)));
}
else if(pin/32 < 4){
*gpio3.oe = *gpio3.oe & (~(1<<(pin-96)));
}
} }
} }
int8_t LinuxGPIO::analogPinToDigitalPin(uint8_t pin) int8_t LinuxGPIO::analogPinToDigitalPin(uint8_t pin)
{ {
return -1; return -1;
@ -123,54 +79,29 @@ int8_t LinuxGPIO::analogPinToDigitalPin(uint8_t pin)
uint8_t LinuxGPIO::read(uint8_t pin) { uint8_t LinuxGPIO::read(uint8_t pin) {
uint8_t value;
if(pin/32 < 1){ uint8_t bank = pin/32;
value = (bool)(*gpio0.in & (1<<pin)); uint8_t bankpin = pin & 0x1F;
} if (bank >= LINUX_GPIO_NUM_BANKS) {
else if(pin/32 < 2){ hal.scheduler->panic("invalid pin number");
value = (bool)(*gpio1.in & (1<<(pin-32))); return 0;
}
else if(pin/32 < 3){
value = (bool)(*gpio2.in & (1<<(pin-64)));
}
else if(pin/32 < 4){
value = (bool)(*gpio3.in & (1<<(pin-96)));
} }
return *gpio_bank[bank].in & (1U<<bankpin) ? HIGH : LOW;
return value;
} }
void LinuxGPIO::write(uint8_t pin, uint8_t value) void LinuxGPIO::write(uint8_t pin, uint8_t value)
{ {
if(value == HIGH){ uint8_t bank = pin/32;
if(pin/32 < 1){ uint8_t bankpin = pin & 0x1F;
*gpio0.out = *gpio0.out | (1<<pin); if (bank >= LINUX_GPIO_NUM_BANKS) {
} hal.scheduler->panic("invalid pin number");
else if(pin/32 < 2){ return;
*gpio1.out = *gpio1.out | (1<<(pin-32));
}
else if(pin/32 < 3){
*gpio2.out = *gpio2.out | (1<<(pin-64));
}
else if(pin/32 < 4){
*gpio3.out = *gpio3.out | (1<<(pin-96));
}
} }
else{ if (value == LOW) {
if(pin/32 < 1){ *gpio_bank[bank].out &= ~(1U<<bankpin);
*gpio0.out = *gpio0.out & (~(1<<pin)); } else {
} *gpio_bank[bank].out |= 1U<<bankpin;
else if(pin/32 < 2){
*gpio1.out = *gpio1.out & (~(1<<(pin-32)));
}
else if(pin/32 < 3){
*gpio2.out = *gpio2.out & (~(1<<(pin-64)));
}
else if(pin/32 < 4){
*gpio3.out = *gpio3.out & (~(1<<(pin-96)));
}
} }
} }
@ -185,8 +116,8 @@ AP_HAL::DigitalSource* LinuxGPIO::channel(uint16_t n) {
} }
/* Interrupt interface: */ /* Interrupt interface: */
bool LinuxGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, bool LinuxGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
uint8_t mode) { {
return true; return true;
} }
@ -198,98 +129,26 @@ bool LinuxGPIO::usb_connected(void)
LinuxDigitalSource::LinuxDigitalSource(uint8_t v) : LinuxDigitalSource::LinuxDigitalSource(uint8_t v) :
_v(v) _v(v)
{ {
} }
void LinuxDigitalSource::mode(uint8_t output) void LinuxDigitalSource::mode(uint8_t output)
{ {
uint8_t pin = _v; hal.gpio->pinMode(_v, output);
if(output == GPIO_INPUT){
if(pin/32 < 1){
*gpio0.oe = *gpio0.oe | (1<<pin);
}
else if(pin/32 < 2){
*gpio1.oe = *gpio1.oe | (1<<(pin-32));
}
else if(pin/32 < 3){
*gpio2.oe = *gpio2.oe | (1<<(pin-64));
}
else if(pin/32 < 4){
*gpio3.oe = *gpio3.oe | (1<<(pin-96));
}
}
else{
if(pin/32 < 1){
*gpio0.oe = *gpio0.oe & (~(1<<pin));
}
else if(pin/32 < 2){
*gpio1.oe = *gpio1.oe & (~(1<<(pin-32)));
}
else if(pin/32 < 3){
*gpio2.oe = *gpio2.oe & (~(1<<(pin-64)));
}
else if(pin/32 < 4){
*gpio3.oe = *gpio3.oe & (~(1<<(pin-96)));
}
}
} }
uint8_t LinuxDigitalSource::read() { uint8_t LinuxDigitalSource::read()
uint8_t value, pin = _v; {
return hal.gpio->read(_v);
if(pin/32 < 1){
value = (bool)(*gpio0.in & (1<<pin));
}
else if(pin/32 < 2){
value = (bool)(*gpio1.in & (1<<(pin-32)));
}
else if(pin/32 < 3){
value = (bool)(*gpio2.in & (1<<(pin-64)));
}
else if(pin/32 < 4){
value = (bool)(*gpio3.in & (1<<(pin-96)));
}
return value;
} }
void LinuxDigitalSource::write(uint8_t value) { void LinuxDigitalSource::write(uint8_t value)
{
uint8_t pin = _v; return hal.gpio->write(_v,value);
if(value == HIGH){
if(pin/32 < 1){
*gpio0.out = *gpio0.out | (1<<pin);
}
else if(pin/32 < 2){
*gpio1.out = *gpio1.out | (1<<(pin-32));
}
else if(pin/32 < 3){
*gpio2.out = *gpio2.out | (1<<(pin-64));
}
else if(pin/32 < 4){
*gpio3.out = *gpio3.out | (1<<(pin-96));
}
}
else{
if(pin/32 < 1){
*gpio0.out = *gpio0.out & (~(1<<pin));
}
else if(pin/32 < 2){
*gpio1.out = *gpio1.out & (~(1<<(pin-32)));
}
else if(pin/32 < 3){
*gpio2.out = *gpio2.out & (~(1<<(pin-64)));
}
else if(pin/32 < 4){
*gpio3.out = *gpio3.out & (~(1<<(pin-96)));
}
}
} }
void LinuxDigitalSource::toggle() { void LinuxDigitalSource::toggle()
{
write(!read()); write(!read());
} }

12
libraries/AP_HAL_Linux/GPIO.h

@ -25,6 +25,8 @@
#define LOW 0 #define LOW 0
#define HIGH 1 #define HIGH 1
#define LINUX_GPIO_NUM_BANKS 4
// BeagleBone Black GPIO mappings // BeagleBone Black GPIO mappings
#define BBB_USR0 53 #define BBB_USR0 53
#define BBB_USR1 54 #define BBB_USR1 54
@ -98,8 +100,15 @@
#define BBB_P9_41 20 #define BBB_P9_41 20
#define BBB_P9_42 7 #define BBB_P9_42 7
class Linux::LinuxGPIO : public AP_HAL::GPIO { class Linux::LinuxGPIO : public AP_HAL::GPIO {
private:
struct GPIO {
volatile uint32_t *base;
volatile uint32_t *oe;
volatile uint32_t *in;
volatile uint32_t *out;
} gpio_bank[LINUX_GPIO_NUM_BANKS];
public: public:
LinuxGPIO(); LinuxGPIO();
void init(); void init();
@ -129,6 +138,7 @@ public:
void toggle(); void toggle();
private: private:
uint8_t _v; uint8_t _v;
}; };
#endif // __AP_HAL_LINUX_GPIO_H__ #endif // __AP_HAL_LINUX_GPIO_H__

Loading…
Cancel
Save