3 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \ 4 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || \ 5 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI || \ 6 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE || \ 7 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET 20 using namespace Linux;
27 #if LINUX_GPIO_NUM_BANKS == 4 33 uint8_t bank_enable[3] = { 5, 65, 105 };
34 int export_fd =
open(
"/sys/class/gpio/export", O_WRONLY | O_CLOEXEC);
35 if (export_fd == -1) {
38 for (uint8_t i=0; i<3; i++) {
39 dprintf(export_fd,
"%u\n", (
unsigned)bank_enable[i]);
45 if ((mem_fd =
open(
"/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC)) < 0) {
46 printf(
"can't open /dev/mem \n");
53 gpio_bank[i].
base = (
volatile unsigned *)mmap(0,
GPIO_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, offsets[i]);
63 #endif // LINUX_GPIO_NUM_BANKS 68 uint8_t bank = pin/32;
69 uint8_t bankpin = pin & 0x1F;
88 uint8_t bank = pin/32;
89 uint8_t bankpin = pin & 0x1F;
99 uint8_t bank = pin/32;
100 uint8_t bankpin = pin & 0x1F;
132 #endif // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || int8_t analogPinToDigitalPin(uint8_t pin)
void pinMode(uint8_t pin, uint8_t output)
int printf(const char *fmt,...)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
#define LINUX_GPIO_NUM_BANKS
uint8_t read(uint8_t pin)
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
AP_HAL::DigitalSource * channel(uint16_t n)
int close(int fileno)
POSIX Close a file with fileno handel.
void write(uint8_t pin, uint8_t value)
void panic(const char *errormsg,...) FMT_PRINTF(1
struct Linux::GPIO_BBB::GPIO gpio_bank[LINUX_GPIO_NUM_BANKS]