3 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \ 4 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \ 5 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \ 6 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI 22 #define BCM2708_PERI_BASE 0x20000000 23 #define BCM2709_PERI_BASE 0x3F000000 24 #define GPIO_BASE(address) (address + 0x200000) 27 #define GPIO_MODE_IN(g) *(_gpio+((g)/10)) &= ~(7<<(((g)%10)*3)) 28 #define GPIO_MODE_OUT(g) *(_gpio+((g)/10)) |= (1<<(((g)%10)*3)) 29 #define GPIO_MODE_ALT(g,a) *(_gpio+(((g)/10))) |= (((a)<=3?(a)+4:(a)==4?3:2)<<(((g)%10)*3)) 30 #define GPIO_SET_HIGH *(_gpio+7) // sets bits which are 1 31 #define GPIO_SET_LOW *(_gpio+10) // clears bits which are 1 32 #define GPIO_GET(g) (*(_gpio+13)&(1<<g)) // 0 if LOW, (1<<g) if HIGH 34 using namespace Linux;
47 int mem_fd =
open(
"/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
53 void *gpio_map = mmap(
64 if (gpio_map == MAP_FAILED) {
68 _gpio = (
volatile uint32_t *)gpio_map;
#define BCM2709_PERI_BASE
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::DigitalSource * channel(uint16_t n)
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
#define GPIO_BASE(address)
static const AP_HAL::HAL & hal
#define GPIO_MODE_ALT(g, a)
#define BCM2708_PERI_BASE
void pinMode(uint8_t pin, uint8_t output)
int close(int fileno)
POSIX Close a file with fileno handel.
int8_t analogPinToDigitalPin(uint8_t pin)
void write(uint8_t pin, uint8_t value)
int get_rpi_version() const
static UtilRPI * from(AP_HAL::Util *util)
volatile uint32_t * _gpio
void panic(const char *errormsg,...) FMT_PRINTF(1
uint8_t read(uint8_t pin)