HAL_Linux: allow different SPI and GPIO devices on different boards
this fixes the Replay utility, which uses subtype NONE, and will make it easier to port to new boards
This commit is contained in:
parent
003806fcc1
commit
6312b9f8c0
@ -21,6 +21,7 @@ LinuxGPIO::LinuxGPIO()
|
||||
|
||||
void LinuxGPIO::init()
|
||||
{
|
||||
#if LINUX_GPIO_NUM_BANKS == 4
|
||||
int mem_fd;
|
||||
// Enable all GPIO banks
|
||||
// Without this, access to deactivated banks (i.e. those with no clock source set up) will (logically) fail with SIGBUS
|
||||
@ -56,6 +57,7 @@ void LinuxGPIO::init()
|
||||
}
|
||||
|
||||
close(mem_fd);
|
||||
#endif // LINUX_GPIO_NUM_BANKS
|
||||
}
|
||||
|
||||
void LinuxGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
@ -71,6 +73,7 @@ void LinuxGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
*gpio_bank[bank].oe &= ~(1U<<bankpin);
|
||||
}
|
||||
}
|
||||
|
||||
int8_t LinuxGPIO::analogPinToDigitalPin(uint8_t pin)
|
||||
{
|
||||
return -1;
|
||||
|
@ -25,7 +25,12 @@
|
||||
#define LOW 0
|
||||
#define HIGH 1
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
|
||||
#define LINUX_GPIO_NUM_BANKS 4
|
||||
#else
|
||||
// disable GPIO
|
||||
#define LINUX_GPIO_NUM_BANKS 0
|
||||
#endif
|
||||
|
||||
// BeagleBone Black GPIO mappings
|
||||
#define BBB_USR0 53
|
||||
|
@ -143,6 +143,9 @@ uint8_t LinuxI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
uint8_t LinuxI2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t len, uint8_t* data)
|
||||
{
|
||||
if (_fd == -1) {
|
||||
return 1;
|
||||
}
|
||||
struct i2c_msg msgs[] = {
|
||||
{
|
||||
addr : addr,
|
||||
@ -177,6 +180,9 @@ uint8_t LinuxI2CDriver::readRegistersMultiple(uint8_t addr, uint8_t reg,
|
||||
uint8_t len,
|
||||
uint8_t count, uint8_t* data)
|
||||
{
|
||||
if (_fd == -1) {
|
||||
return 1;
|
||||
}
|
||||
while (count > 0) {
|
||||
uint8_t n = count>8?8:count;
|
||||
struct i2c_msg msgs[2*n];
|
||||
|
@ -20,20 +20,26 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define MHZ (1000U*1000U)
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES] = {
|
||||
LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_MS5611, SPI_MODE_3, 8, BBB_P9_42, 6*MHZ, 6*MHZ),
|
||||
LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_MPU6000, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ),
|
||||
// different SPI tables per board subtype
|
||||
LinuxSPIDeviceDriver(1, AP_HAL::SPIDevice_MS5611, SPI_MODE_3, 8, BBB_P9_42, 6*MHZ, 6*MHZ),
|
||||
LinuxSPIDeviceDriver(1, AP_HAL::SPIDevice_MPU6000, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ),
|
||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||
LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_MPU9250, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ),
|
||||
LinuxSPIDeviceDriver(0, LINUX_SPI_DEVICE_LSM9DS0, SPI_MODE_3, 8, BBB_P9_17, 10*MHZ,10*MHZ),
|
||||
LinuxSPIDeviceDriver(1, LINUX_SPI_DEVICE_FRAM, SPI_MODE_0, 8, BBB_P8_12, 6*MHZ, 6*MHZ)
|
||||
LinuxSPIDeviceDriver(1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ),
|
||||
LinuxSPIDeviceDriver(0, AP_HAL::SPIDevice_LSM9DS0, SPI_MODE_3, 8, BBB_P9_17, 10*MHZ,10*MHZ),
|
||||
LinuxSPIDeviceDriver(1, AP_HAL::SPIDevice_FRAM, SPI_MODE_0, 8, BBB_P8_12, 6*MHZ, 6*MHZ)
|
||||
};
|
||||
#else
|
||||
// empty device table
|
||||
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[0];
|
||||
#endif
|
||||
|
||||
// have a separate semaphore per bus
|
||||
LinuxSemaphore LinuxSPIDeviceManager::_semaphore[LINUX_SPI_NUM_BUSES];
|
||||
int LinuxSPIDeviceManager::_fd[LINUX_SPI_NUM_BUSES];
|
||||
|
||||
LinuxSPIDeviceDriver::LinuxSPIDeviceDriver(uint8_t bus, LinuxSPIDeviceType type, uint8_t mode, uint8_t bitsPerWord, uint8_t cs_pin, uint32_t lowspeed, uint32_t highspeed):
|
||||
LinuxSPIDeviceDriver::LinuxSPIDeviceDriver(uint8_t bus, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, uint8_t cs_pin, uint32_t lowspeed, uint32_t highspeed):
|
||||
_bus(bus),
|
||||
_type(type),
|
||||
_mode(mode),
|
||||
@ -112,23 +118,27 @@ void LinuxSPIDeviceManager::init(void *)
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceManager::cs_assert(LinuxSPIDeviceType type)
|
||||
void LinuxSPIDeviceManager::cs_assert(enum AP_HAL::SPIDevice type)
|
||||
{
|
||||
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
||||
if (_device[i]._bus != _device[type]._bus) {
|
||||
// not the same bus
|
||||
continue;
|
||||
}
|
||||
if (i != type) {
|
||||
if (_device[i]._type != type) {
|
||||
if (_device[i]._cs->read() != 1) {
|
||||
hal.scheduler->panic("two CS enabled at once");
|
||||
}
|
||||
}
|
||||
}
|
||||
_device[type]._cs->write(0);
|
||||
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
||||
if (_device[i]._type == type) {
|
||||
_device[type]._cs->write(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceManager::cs_release(LinuxSPIDeviceType type)
|
||||
void LinuxSPIDeviceManager::cs_release(enum AP_HAL::SPIDevice type)
|
||||
{
|
||||
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
||||
if (_device[i]._bus != _device[type]._bus) {
|
||||
@ -168,20 +178,12 @@ void LinuxSPIDeviceManager::transaction(LinuxSPIDeviceDriver &driver, const uint
|
||||
/*
|
||||
return a SPIDeviceDriver for a particular device
|
||||
*/
|
||||
AP_HAL::SPIDeviceDriver* LinuxSPIDeviceManager::device(enum AP_HAL::SPIDevice dev)
|
||||
AP_HAL::SPIDeviceDriver *LinuxSPIDeviceManager::device(enum AP_HAL::SPIDevice dev)
|
||||
{
|
||||
switch (dev) {
|
||||
case AP_HAL::SPIDevice_MPU6000:
|
||||
return &_device[LINUX_SPI_DEVICE_MPU6000];
|
||||
case AP_HAL::SPIDevice_MPU9250:
|
||||
return &_device[LINUX_SPI_DEVICE_MPU9250];
|
||||
case AP_HAL::SPIDevice_MS5611:
|
||||
return &_device[LINUX_SPI_DEVICE_MS5611];
|
||||
case AP_HAL::SPIDevice_LSM9DS0:
|
||||
return &_device[LINUX_SPI_DEVICE_LSM9DS0];
|
||||
case AP_HAL::SPIDevice_Dataflash:
|
||||
return &_device[LINUX_SPI_DEVICE_FRAM];
|
||||
|
||||
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
||||
if (_device[i]._type == dev) {
|
||||
return &_device[i];
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
@ -5,21 +5,18 @@
|
||||
#include <AP_HAL_Linux.h>
|
||||
#include "Semaphores.h"
|
||||
|
||||
enum LinuxSPIDeviceType {
|
||||
LINUX_SPI_DEVICE_MS5611 = 0,
|
||||
LINUX_SPI_DEVICE_MPU6000 = 1,
|
||||
LINUX_SPI_DEVICE_MPU9250 = 2,
|
||||
LINUX_SPI_DEVICE_LSM9DS0 = 3,
|
||||
LINUX_SPI_DEVICE_FRAM = 4,
|
||||
LINUX_SPI_DEVICE_NUM_DEVICES = 5
|
||||
};
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
|
||||
#define LINUX_SPI_NUM_BUSES 2
|
||||
#define LINUX_SPI_DEVICE_NUM_DEVICES 5
|
||||
#else
|
||||
#define LINUX_SPI_NUM_BUSES 0
|
||||
#define LINUX_SPI_DEVICE_NUM_DEVICES 0
|
||||
#endif
|
||||
|
||||
class Linux::LinuxSPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
|
||||
public:
|
||||
friend class Linux::LinuxSPIDeviceManager;
|
||||
LinuxSPIDeviceDriver(uint8_t bus, LinuxSPIDeviceType type, uint8_t mode, uint8_t bitsPerWord, uint8_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
|
||||
LinuxSPIDeviceDriver(uint8_t bus, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, uint8_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
|
||||
void init();
|
||||
AP_HAL::Semaphore *get_semaphore();
|
||||
void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
@ -38,7 +35,7 @@ private:
|
||||
uint32_t _lowspeed;
|
||||
uint32_t _highspeed;
|
||||
uint32_t _speed;
|
||||
LinuxSPIDeviceType _type;
|
||||
enum AP_HAL::SPIDevice _type;
|
||||
uint8_t _bus;
|
||||
};
|
||||
|
||||
@ -49,8 +46,8 @@ public:
|
||||
|
||||
static AP_HAL::Semaphore *get_semaphore(uint8_t bus);
|
||||
|
||||
static void cs_assert(enum LinuxSPIDeviceType type);
|
||||
static void cs_release(enum LinuxSPIDeviceType type);
|
||||
static void cs_assert(enum AP_HAL::SPIDevice type);
|
||||
static void cs_release(enum AP_HAL::SPIDevice type);
|
||||
static void transaction(LinuxSPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
|
||||
private:
|
||||
|
Loading…
Reference in New Issue
Block a user