mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_HAL_Linux: remove SPIDriver
SPIDevice now controls all accesses to SPI bus.
This commit is contained in:
parent
5ab1c6ff51
commit
7b140da6d1
@ -8,7 +8,6 @@
|
|||||||
#include "SPIUARTDriver.h"
|
#include "SPIUARTDriver.h"
|
||||||
#include "RPIOUARTDriver.h"
|
#include "RPIOUARTDriver.h"
|
||||||
#include "I2CDevice.h"
|
#include "I2CDevice.h"
|
||||||
#include "SPIDriver.h"
|
|
||||||
#include "AnalogIn_ADS1115.h"
|
#include "AnalogIn_ADS1115.h"
|
||||||
#include "AnalogIn_IIO.h"
|
#include "AnalogIn_IIO.h"
|
||||||
#include "AnalogIn_Raspilot.h"
|
#include "AnalogIn_Raspilot.h"
|
||||||
|
@ -11,6 +11,7 @@
|
|||||||
|
|
||||||
#include "AP_HAL_Linux_Private.h"
|
#include "AP_HAL_Linux_Private.h"
|
||||||
#include "HAL_Linux_Class.h"
|
#include "HAL_Linux_Class.h"
|
||||||
|
#include "SPIDevice.h"
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
@ -301,7 +302,6 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
|
|||||||
|
|
||||||
scheduler->init();
|
scheduler->init();
|
||||||
gpio->init();
|
gpio->init();
|
||||||
spi->init();
|
|
||||||
rcout->init();
|
rcout->init();
|
||||||
rcin->init();
|
rcin->init();
|
||||||
uartA->begin(115200);
|
uartA->begin(115200);
|
||||||
|
@ -31,12 +31,106 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL/utility/OwnPtr.h>
|
#include <AP_HAL/utility/OwnPtr.h>
|
||||||
|
|
||||||
|
#include "GPIO.h"
|
||||||
#include "Util.h"
|
#include "Util.h"
|
||||||
|
|
||||||
namespace Linux {
|
namespace Linux {
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
|
#define MHZ (1000U*1000U)
|
||||||
|
#define KHZ (1000U)
|
||||||
|
#define SPI_CS_KERNEL -1
|
||||||
|
|
||||||
|
struct SPIDesc {
|
||||||
|
SPIDesc(const char *name_, uint16_t bus_, uint16_t subdev_, uint8_t mode_,
|
||||||
|
uint8_t bits_per_word_, int16_t cs_pin_, uint32_t lowspeed_,
|
||||||
|
uint32_t highspeed_)
|
||||||
|
: name(name_), bus(bus_), subdev(subdev_), mode(mode_)
|
||||||
|
, bits_per_word(bits_per_word_), cs_pin(cs_pin_), lowspeed(lowspeed_)
|
||||||
|
, highspeed(highspeed_)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *name;
|
||||||
|
uint16_t bus;
|
||||||
|
uint16_t subdev;
|
||||||
|
uint8_t mode;
|
||||||
|
uint8_t bits_per_word;
|
||||||
|
int16_t cs_pin;
|
||||||
|
uint32_t lowspeed;
|
||||||
|
uint32_t highspeed;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = {
|
||||||
|
// different SPI tables per board subtype
|
||||||
|
SPIDesc("lsm9ds0_am", 1, 0, SPI_MODE_3, 8, BBB_P9_17, 10*MHZ,10*MHZ),
|
||||||
|
SPIDesc("lsm9ds0_g", 1, 0, SPI_MODE_3, 8, BBB_P8_9, 10*MHZ,10*MHZ),
|
||||||
|
SPIDesc("ms5611", 2, 0, SPI_MODE_3, 8, BBB_P9_42, 10*MHZ,10*MHZ),
|
||||||
|
SPIDesc("mpu6000", 2, 0, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ),
|
||||||
|
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||||
|
SPIDesc("mpu9250", 2, 0, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ),
|
||||||
|
};
|
||||||
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = {
|
||||||
|
SPIDesc("mpu6000", 0, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 15*MHZ)
|
||||||
|
};
|
||||||
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = {
|
||||||
|
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||||
|
SPIDesc("mpu9250", 0, 1, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||||
|
SPIDesc("ublox", 0, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 5*MHZ, 5*MHZ),
|
||||||
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
||||||
|
SPIDesc("lsm9ds1_m", 0, 2, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
|
||||||
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = {
|
||||||
|
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||||
|
SPIDesc("mpu9250", 0, 1, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||||
|
SPIDesc("ms5611", 0, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*KHZ, 10*MHZ),
|
||||||
|
};
|
||||||
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = {
|
||||||
|
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||||
|
SPIDesc("mpu9250", 2, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||||
|
SPIDesc("mpu9250ext", 1, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
||||||
|
SPIDesc("ms5611", 2, 1, SPI_MODE_3, 8, SPI_CS_KERNEL, 10*MHZ,10*MHZ),
|
||||||
|
};
|
||||||
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = {
|
||||||
|
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||||
|
SPIDesc("mpu6000", 0, 0, SPI_MODE_3, 8, RPI_GPIO_25, 1*MHZ, 20*MHZ),
|
||||||
|
SPIDesc("ms5611", 0, 0, SPI_MODE_3, 8, RPI_GPIO_23, 10*MHZ, 10*MHZ),
|
||||||
|
SPIDesc("lsm9ds0_am", 0, 0, SPI_MODE_3, 8, RPI_GPIO_22, 10*MHZ, 10*MHZ),
|
||||||
|
SPIDesc("lsm9ds0_g", 0, 0, SPI_MODE_3, 8, RPI_GPIO_12, 10*MHZ, 10*MHZ),
|
||||||
|
SPIDesc("raspio", 0, 0, SPI_MODE_3, 8, RPI_GPIO_7, 10*MHZ, 10*MHZ),
|
||||||
|
};
|
||||||
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = {
|
||||||
|
SPIDesc("mpu9250", 0, 0, SPI_MODE_0, 8, RPI_GPIO_7, 1*MHZ, 20*MHZ),
|
||||||
|
SPIDesc("ublox", 0, 0, SPI_MODE_0, 8, RPI_GPIO_8, 250*KHZ, 5*MHZ),
|
||||||
|
};
|
||||||
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = {
|
||||||
|
SPIDesc("bebop", 1, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 320*KHZ, 320*KHZ),
|
||||||
|
};
|
||||||
|
#else
|
||||||
|
// empty device table
|
||||||
|
SPIDesc SPIDeviceManager::_device[] = { };
|
||||||
|
#define LINUX_SPI_DEVICE_NUM_DEVICES 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LINUX_SPI_DEVICE_NUM_DEVICES
|
||||||
|
#define LINUX_SPI_DEVICE_NUM_DEVICES ARRAY_SIZE(SPIDeviceManager::_device)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
const uint8_t SPIDeviceManager::_n_device_desc = LINUX_SPI_DEVICE_NUM_DEVICES;
|
||||||
|
|
||||||
|
|
||||||
/* Private struct to maintain for each bus */
|
/* Private struct to maintain for each bus */
|
||||||
class SPIBus {
|
class SPIBus {
|
||||||
public:
|
public:
|
||||||
@ -75,13 +169,22 @@ public:
|
|||||||
uint8_t ref;
|
uint8_t ref;
|
||||||
};
|
};
|
||||||
|
|
||||||
SPIDevice::SPIDevice(SPIBus &bus, SPIDeviceDriver &device_desc)
|
SPIDevice::SPIDevice(SPIBus &bus, SPIDesc &device_desc)
|
||||||
: _bus(bus)
|
: _bus(bus)
|
||||||
, _desc(device_desc)
|
, _desc(device_desc)
|
||||||
{
|
{
|
||||||
_desc.init();
|
if (_desc.cs_pin != SPI_CS_KERNEL) {
|
||||||
|
_cs = hal.gpio->channel(_desc.cs_pin);
|
||||||
|
if (!_cs) {
|
||||||
|
AP_HAL::panic("Unable to instantiate cs pin");
|
||||||
|
}
|
||||||
|
|
||||||
|
_cs->mode(HAL_GPIO_OUTPUT);
|
||||||
|
|
||||||
|
// do not hold the SPI bus initially
|
||||||
_cs_release();
|
_cs_release();
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
SPIDevice::~SPIDevice()
|
SPIDevice::~SPIDevice()
|
||||||
{
|
{
|
||||||
@ -93,10 +196,10 @@ bool SPIDevice::set_speed(AP_HAL::Device::Speed speed)
|
|||||||
{
|
{
|
||||||
switch (speed) {
|
switch (speed) {
|
||||||
case AP_HAL::Device::SPEED_HIGH:
|
case AP_HAL::Device::SPEED_HIGH:
|
||||||
_desc._speed = _desc._highspeed;
|
_speed = _desc.highspeed;
|
||||||
break;
|
break;
|
||||||
case AP_HAL::Device::SPEED_LOW:
|
case AP_HAL::Device::SPEED_LOW:
|
||||||
_desc._speed = _desc._lowspeed;
|
_speed = _desc.lowspeed;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -115,9 +218,9 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
|||||||
msgs[nmsgs].tx_buf = (uint64_t) send;
|
msgs[nmsgs].tx_buf = (uint64_t) send;
|
||||||
msgs[nmsgs].rx_buf = 0;
|
msgs[nmsgs].rx_buf = 0;
|
||||||
msgs[nmsgs].len = send_len;
|
msgs[nmsgs].len = send_len;
|
||||||
msgs[nmsgs].speed_hz = _desc._speed;
|
msgs[nmsgs].speed_hz = _speed;
|
||||||
msgs[nmsgs].delay_usecs = 0;
|
msgs[nmsgs].delay_usecs = 0;
|
||||||
msgs[nmsgs].bits_per_word = _desc._bitsPerWord;
|
msgs[nmsgs].bits_per_word = _desc.bits_per_word;
|
||||||
msgs[nmsgs].cs_change = 0;
|
msgs[nmsgs].cs_change = 0;
|
||||||
nmsgs++;
|
nmsgs++;
|
||||||
}
|
}
|
||||||
@ -126,9 +229,9 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
|||||||
msgs[nmsgs].tx_buf = 0;
|
msgs[nmsgs].tx_buf = 0;
|
||||||
msgs[nmsgs].rx_buf = (uint64_t) recv;
|
msgs[nmsgs].rx_buf = (uint64_t) recv;
|
||||||
msgs[nmsgs].len = recv_len;
|
msgs[nmsgs].len = recv_len;
|
||||||
msgs[nmsgs].speed_hz = _desc._speed;
|
msgs[nmsgs].speed_hz = _speed;
|
||||||
msgs[nmsgs].delay_usecs = 0;
|
msgs[nmsgs].delay_usecs = 0;
|
||||||
msgs[nmsgs].bits_per_word = _desc._bitsPerWord;
|
msgs[nmsgs].bits_per_word = _desc.bits_per_word;
|
||||||
msgs[nmsgs].cs_change = 0;
|
msgs[nmsgs].cs_change = 0;
|
||||||
nmsgs++;
|
nmsgs++;
|
||||||
}
|
}
|
||||||
@ -137,7 +240,7 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
int r = ioctl(_bus.fd, SPI_IOC_WR_MODE, &_desc._mode);
|
int r = ioctl(_bus.fd, SPI_IOC_WR_MODE, &_desc.mode);
|
||||||
if (r < 0) {
|
if (r < 0) {
|
||||||
hal.console->printf("SPIDevice: error on setting mode fd=%d (%s)\n",
|
hal.console->printf("SPIDevice: error on setting mode fd=%d (%s)\n",
|
||||||
_bus.fd, strerror(errno));
|
_bus.fd, strerror(errno));
|
||||||
@ -171,12 +274,12 @@ bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv,
|
|||||||
msgs[0].tx_buf = (uint64_t) send;
|
msgs[0].tx_buf = (uint64_t) send;
|
||||||
msgs[0].rx_buf = (uint64_t) recv;
|
msgs[0].rx_buf = (uint64_t) recv;
|
||||||
msgs[0].len = len;
|
msgs[0].len = len;
|
||||||
msgs[0].speed_hz = _desc._speed;
|
msgs[0].speed_hz = _speed;
|
||||||
msgs[0].delay_usecs = 0;
|
msgs[0].delay_usecs = 0;
|
||||||
msgs[0].bits_per_word = _desc._bitsPerWord;
|
msgs[0].bits_per_word = _desc.bits_per_word;
|
||||||
msgs[0].cs_change = 0;
|
msgs[0].cs_change = 0;
|
||||||
|
|
||||||
int r = ioctl(_bus.fd, SPI_IOC_WR_MODE, &_desc._mode);
|
int r = ioctl(_bus.fd, SPI_IOC_WR_MODE, &_desc.mode);
|
||||||
if (r < 0) {
|
if (r < 0) {
|
||||||
hal.console->printf("SPIDevice: error on setting mode fd=%d (%s)\n",
|
hal.console->printf("SPIDevice: error on setting mode fd=%d (%s)\n",
|
||||||
_bus.fd, strerror(errno));
|
_bus.fd, strerror(errno));
|
||||||
@ -199,20 +302,20 @@ bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv,
|
|||||||
|
|
||||||
void SPIDevice::_cs_assert()
|
void SPIDevice::_cs_assert()
|
||||||
{
|
{
|
||||||
if (_desc._cs_pin == SPI_CS_KERNEL) {
|
if (_desc.cs_pin == SPI_CS_KERNEL) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
_desc._cs->write(0);
|
_cs->write(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPIDevice::_cs_release()
|
void SPIDevice::_cs_release()
|
||||||
{
|
{
|
||||||
if (_desc._cs_pin == SPI_CS_KERNEL) {
|
if (_desc.cs_pin == SPI_CS_KERNEL) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
_desc._cs->write(1);
|
_cs->write(1);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_HAL::Semaphore *SPIDevice::get_semaphore()
|
AP_HAL::Semaphore *SPIDevice::get_semaphore()
|
||||||
@ -228,11 +331,11 @@ int SPIDevice::get_fd()
|
|||||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
|
||||||
SPIDeviceManager::get_device(const char *name)
|
SPIDeviceManager::get_device(const char *name)
|
||||||
{
|
{
|
||||||
SPIDeviceDriver *desc = nullptr;
|
SPIDesc *desc = nullptr;
|
||||||
|
|
||||||
/* Find the bus description in the table */
|
/* Find the bus description in the table */
|
||||||
for (uint8_t i = 0; i < _n_device_desc; i++) {
|
for (uint8_t i = 0; i < _n_device_desc; i++) {
|
||||||
if (!strcmp(_device[i]._name, name)) {
|
if (!strcmp(_device[i].name, name)) {
|
||||||
desc = &_device[i];
|
desc = &_device[i];
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -242,31 +345,21 @@ SPIDeviceManager::get_device(const char *name)
|
|||||||
AP_HAL::panic("SPI: invalid device name");
|
AP_HAL::panic("SPI: invalid device name");
|
||||||
}
|
}
|
||||||
|
|
||||||
return get_device(*desc);
|
|
||||||
}
|
|
||||||
|
|
||||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
|
|
||||||
SPIDeviceManager::get_device(SPIDeviceDriver &desc)
|
|
||||||
{
|
|
||||||
/* Find if bus is already open */
|
/* Find if bus is already open */
|
||||||
for (uint8_t i = 0, n = _buses.size(); i < n; i++) {
|
for (uint8_t i = 0, n = _buses.size(); i < n; i++) {
|
||||||
if (_buses[i]->bus == desc._bus &&
|
if (_buses[i]->bus == desc->bus &&
|
||||||
_buses[i]->kernel_cs == desc._subdev) {
|
_buses[i]->kernel_cs == desc->subdev) {
|
||||||
return _create_device(*_buses[i], desc);
|
return _create_device(*_buses[i], *desc);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Bus not found for this device, create a new one */
|
/* Bus not found for this device, create a new one */
|
||||||
AP_HAL::OwnPtr<SPIBus> b{new SPIBus()};
|
AP_HAL::OwnPtr<SPIBus> b{new SPIBus()};
|
||||||
if (!b) {
|
if (!b || b->open(desc->bus, desc->subdev) < 0) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (b->open(desc._bus, desc._subdev) < 0) {
|
auto dev = _create_device(*b, *desc);
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
auto dev = _create_device(*b, desc);
|
|
||||||
if (!dev) {
|
if (!dev) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
@ -278,7 +371,7 @@ SPIDeviceManager::get_device(SPIDeviceDriver &desc)
|
|||||||
|
|
||||||
/* Create a new device increasing the bus reference */
|
/* Create a new device increasing the bus reference */
|
||||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
|
||||||
SPIDeviceManager::_create_device(SPIBus &b, SPIDeviceDriver &desc) const
|
SPIDeviceManager::_create_device(SPIBus &b, SPIDesc &desc) const
|
||||||
{
|
{
|
||||||
auto dev = AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(b, desc));
|
auto dev = AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(b, desc));
|
||||||
if (!dev) {
|
if (!dev) {
|
||||||
|
@ -18,19 +18,19 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
#include <AP_HAL/HAL.h>
|
#include <AP_HAL/HAL.h>
|
||||||
#include <AP_HAL/SPIDevice.h>
|
#include <AP_HAL/SPIDevice.h>
|
||||||
|
|
||||||
#include "SPIDriver.h"
|
|
||||||
|
|
||||||
namespace Linux {
|
namespace Linux {
|
||||||
|
|
||||||
class SPIBus;
|
class SPIBus;
|
||||||
|
class SPIDesc;
|
||||||
|
|
||||||
class SPIDevice : public AP_HAL::SPIDevice {
|
class SPIDevice : public AP_HAL::SPIDevice {
|
||||||
public:
|
public:
|
||||||
SPIDevice(SPIBus &bus, SPIDeviceDriver &device_desc);
|
SPIDevice(SPIBus &bus, SPIDesc &device_desc);
|
||||||
|
|
||||||
virtual ~SPIDevice();
|
virtual ~SPIDevice();
|
||||||
|
|
||||||
@ -62,7 +62,9 @@ public:
|
|||||||
|
|
||||||
protected:
|
protected:
|
||||||
SPIBus &_bus;
|
SPIBus &_bus;
|
||||||
SPIDeviceDriver &_desc;
|
SPIDesc &_desc;
|
||||||
|
AP_HAL::DigitalSource *_cs;
|
||||||
|
uint32_t _speed;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Select device if using userspace CS
|
* Select device if using userspace CS
|
||||||
@ -75,4 +77,31 @@ protected:
|
|||||||
void _cs_release();
|
void _cs_release();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
class SPIDeviceManager : public AP_HAL::SPIDeviceManager {
|
||||||
|
public:
|
||||||
|
friend class SPIDevice;
|
||||||
|
|
||||||
|
static SPIDeviceManager *from(AP_HAL::SPIDeviceManager *spi_mgr)
|
||||||
|
{
|
||||||
|
return static_cast<SPIDeviceManager*>(spi_mgr);
|
||||||
|
}
|
||||||
|
|
||||||
|
SPIDeviceManager()
|
||||||
|
{
|
||||||
|
/* Reserve space up-front for 3 buses */
|
||||||
|
_buses.reserve(3);
|
||||||
|
}
|
||||||
|
|
||||||
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name);
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void _unregister(SPIBus &b);
|
||||||
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _create_device(SPIBus &b, SPIDesc &device_desc) const;
|
||||||
|
|
||||||
|
std::vector<SPIBus*> _buses;
|
||||||
|
|
||||||
|
static const uint8_t _n_device_desc;
|
||||||
|
static SPIDesc _device[];
|
||||||
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -1,292 +0,0 @@
|
|||||||
#include "SPIDriver.h"
|
|
||||||
|
|
||||||
#include <errno.h>
|
|
||||||
#include <fcntl.h>
|
|
||||||
#include <linux/spi/spidev.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <stdio.h>
|
|
||||||
#include <sys/ioctl.h>
|
|
||||||
#include <sys/stat.h>
|
|
||||||
#include <sys/types.h>
|
|
||||||
#include <unistd.h>
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
|
|
||||||
#include "GPIO.h"
|
|
||||||
|
|
||||||
using namespace Linux;
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
|
||||||
|
|
||||||
#define MHZ (1000U*1000U)
|
|
||||||
#define KHZ (1000U)
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
||||||
// different SPI tables per board subtype
|
|
||||||
SPIDeviceDriver("lsm9ds0_am", 1, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, BBB_P9_17, 10*MHZ,10*MHZ),
|
|
||||||
SPIDeviceDriver("lsm9ds0_g", 1, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, BBB_P8_9, 10*MHZ,10*MHZ),
|
|
||||||
SPIDeviceDriver("ms5611", 2, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, BBB_P9_42, 10*MHZ,10*MHZ),
|
|
||||||
SPIDeviceDriver("mpu6000", 2, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ),
|
|
||||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
|
||||||
SPIDeviceDriver("mpu9250", 2, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ),
|
|
||||||
};
|
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
||||||
SPIDeviceDriver("mpu6000", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 15*MHZ)
|
|
||||||
};
|
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
||||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
|
||||||
SPIDeviceDriver("mpu9250", 0, 1, AP_HAL::SPIDevice_Type, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
|
||||||
SPIDeviceDriver("ublox", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_0, 8, SPI_CS_KERNEL, 5*MHZ, 5*MHZ),
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
|
||||||
SPIDeviceDriver("lsm9ds1_m", 0, 2, AP_HAL::SPIDevice_Type, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
|
|
||||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
||||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
|
||||||
SPIDeviceDriver("mpu9250", 0, 1, AP_HAL::SPIDevice_Type, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
|
||||||
SPIDeviceDriver("ms5611", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*KHZ, 10*MHZ),
|
|
||||||
};
|
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
||||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
|
||||||
SPIDeviceDriver("mpu9250", 2, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
|
||||||
SPIDeviceDriver("mpu9250ext", 1, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 20*MHZ),
|
|
||||||
SPIDeviceDriver("ms5611", 2, 1, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, SPI_CS_KERNEL, 10*MHZ,10*MHZ),
|
|
||||||
};
|
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
||||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
|
||||||
SPIDeviceDriver("mpu6000", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, RPI_GPIO_25, 1*MHZ, 20*MHZ),
|
|
||||||
SPIDeviceDriver("ms5611", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, RPI_GPIO_23, 10*MHZ, 10*MHZ),
|
|
||||||
SPIDeviceDriver("lsm9ds0_am", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, RPI_GPIO_22, 10*MHZ, 10*MHZ),
|
|
||||||
SPIDeviceDriver("lsm9ds0_g", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, RPI_GPIO_12, 10*MHZ, 10*MHZ),
|
|
||||||
SPIDeviceDriver("raspio", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, RPI_GPIO_7, 10*MHZ, 10*MHZ),
|
|
||||||
};
|
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
||||||
SPIDeviceDriver("mpu9250", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_0, 8, RPI_GPIO_7, 1*MHZ, 20*MHZ),
|
|
||||||
SPIDeviceDriver("ublox", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_0, 8, RPI_GPIO_8, 250*KHZ, 5*MHZ),
|
|
||||||
};
|
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|
||||||
SPIDeviceDriver("bebop", 1, 0, AP_HAL::SPIDevice_Type, SPI_MODE_0, 8, SPI_CS_KERNEL, 320*KHZ, 320*KHZ),
|
|
||||||
};
|
|
||||||
#else
|
|
||||||
// empty device table
|
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = { };
|
|
||||||
#define LINUX_SPI_DEVICE_NUM_DEVICES 0
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef LINUX_SPI_DEVICE_NUM_DEVICES
|
|
||||||
#define LINUX_SPI_DEVICE_NUM_DEVICES ARRAY_SIZE(SPIDeviceManager::_device)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
const uint8_t SPIDeviceManager::_n_device_desc = LINUX_SPI_DEVICE_NUM_DEVICES;
|
|
||||||
|
|
||||||
SPIDeviceDriver::SPIDeviceDriver(const char *name, uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDeviceType type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed):
|
|
||||||
_name(name),
|
|
||||||
_bus(bus),
|
|
||||||
_subdev(subdev),
|
|
||||||
_type(type),
|
|
||||||
_mode(mode),
|
|
||||||
_bitsPerWord(bitsPerWord),
|
|
||||||
_lowspeed(lowspeed),
|
|
||||||
_highspeed(highspeed),
|
|
||||||
_speed(highspeed),
|
|
||||||
_cs_pin(cs_pin),
|
|
||||||
_cs(NULL)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
void SPIDeviceDriver::init()
|
|
||||||
{
|
|
||||||
// Init the CS
|
|
||||||
if(_cs_pin != SPI_CS_KERNEL) {
|
|
||||||
_cs = hal.gpio->channel(_cs_pin);
|
|
||||||
if (_cs == NULL) {
|
|
||||||
AP_HAL::panic("Unable to instantiate cs pin");
|
|
||||||
}
|
|
||||||
_cs->mode(HAL_GPIO_OUTPUT);
|
|
||||||
_cs->write(1); // do not hold the SPI bus initially
|
|
||||||
} else {
|
|
||||||
// FIXME Anything we need to do here for kernel-managed CS?
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
AP_HAL::Semaphore *SPIDeviceDriver::get_semaphore()
|
|
||||||
{
|
|
||||||
return _fake_dev->get_semaphore();
|
|
||||||
}
|
|
||||||
|
|
||||||
bool SPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
|
|
||||||
{
|
|
||||||
return SPIDeviceManager::transaction(*this, tx, rx, len);
|
|
||||||
}
|
|
||||||
|
|
||||||
void SPIDeviceDriver::set_bus_speed(enum bus_speed speed)
|
|
||||||
{
|
|
||||||
if (speed == SPI_SPEED_LOW) {
|
|
||||||
_speed = _lowspeed;
|
|
||||||
} else {
|
|
||||||
_speed = _highspeed;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void SPIDeviceDriver::cs_assert()
|
|
||||||
{
|
|
||||||
SPIDeviceManager::cs_assert(_type);
|
|
||||||
}
|
|
||||||
|
|
||||||
void SPIDeviceDriver::cs_release()
|
|
||||||
{
|
|
||||||
SPIDeviceManager::cs_release(_type);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t SPIDeviceDriver::transfer(uint8_t data)
|
|
||||||
{
|
|
||||||
uint8_t v = 0;
|
|
||||||
transaction(&data, &v, 1);
|
|
||||||
return v;
|
|
||||||
}
|
|
||||||
|
|
||||||
void SPIDeviceDriver::transfer(const uint8_t *data, uint16_t len)
|
|
||||||
{
|
|
||||||
transaction(data, NULL, len);
|
|
||||||
}
|
|
||||||
|
|
||||||
void SPIDeviceManager::init()
|
|
||||||
{
|
|
||||||
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
|
||||||
_device[i]._fake_dev = SPIDeviceManager::from(hal.spi)->get_device(_device[i]);
|
|
||||||
if (!_device[i]._fake_dev) {
|
|
||||||
AP_HAL::panic("SPIDriver: couldn't use spidev%u.%u for %s",
|
|
||||||
_device[i]._bus, _device[i]._subdev, _device[i]._name);
|
|
||||||
}
|
|
||||||
_device[i].init();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void SPIDeviceManager::cs_assert(enum AP_HAL::SPIDeviceType type)
|
|
||||||
{
|
|
||||||
uint16_t bus = 0, i;
|
|
||||||
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
|
||||||
if (_device[i]._type == type) {
|
|
||||||
bus = _device[i]._bus;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (i == LINUX_SPI_DEVICE_NUM_DEVICES) {
|
|
||||||
AP_HAL::panic("Bad device type");
|
|
||||||
}
|
|
||||||
|
|
||||||
// Kernel-mode CS handling
|
|
||||||
if(_device[i]._cs_pin == SPI_CS_KERNEL)
|
|
||||||
return;
|
|
||||||
|
|
||||||
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
|
||||||
if (_device[i]._bus != bus) {
|
|
||||||
// not the same bus
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
if (_device[i]._type != type) {
|
|
||||||
if (_device[i]._cs->read() != 1) {
|
|
||||||
hal.console->printf("two CS enabled at once i=%u %u and %u\n",
|
|
||||||
(unsigned)i, (unsigned)type, (unsigned)_device[i]._type);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
|
||||||
if (_device[i]._type == type) {
|
|
||||||
_device[i]._cs->write(0);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void SPIDeviceManager::cs_release(enum AP_HAL::SPIDeviceType type)
|
|
||||||
{
|
|
||||||
uint16_t bus = 0, i;
|
|
||||||
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
|
||||||
if (_device[i]._type == type) {
|
|
||||||
bus = _device[i]._bus;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (i == LINUX_SPI_DEVICE_NUM_DEVICES) {
|
|
||||||
AP_HAL::panic("Bad device type");
|
|
||||||
}
|
|
||||||
|
|
||||||
// Kernel-mode CS handling
|
|
||||||
if(_device[i]._cs_pin == SPI_CS_KERNEL)
|
|
||||||
return;
|
|
||||||
|
|
||||||
for (i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
|
||||||
if (_device[i]._bus != bus) {
|
|
||||||
// not the same bus
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
_device[i]._cs->write(1);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
bool SPIDeviceManager::transaction(SPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len)
|
|
||||||
{
|
|
||||||
int r;
|
|
||||||
// we set the mode before we assert the CS line so that the bus is
|
|
||||||
// in the correct idle state before the chip is selected
|
|
||||||
int fd = driver._fake_dev->get_fd();
|
|
||||||
r = ioctl(fd, SPI_IOC_WR_MODE, &driver._mode);
|
|
||||||
if (r == -1) {
|
|
||||||
hal.console->printf("SPI: error on setting mode\n");
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
cs_assert(driver._type);
|
|
||||||
struct spi_ioc_transfer spi[1];
|
|
||||||
memset(spi, 0, sizeof(spi));
|
|
||||||
spi[0].tx_buf = (uint64_t)tx;
|
|
||||||
spi[0].rx_buf = (uint64_t)rx;
|
|
||||||
spi[0].len = len;
|
|
||||||
spi[0].delay_usecs = 0;
|
|
||||||
spi[0].speed_hz = driver._speed;
|
|
||||||
spi[0].bits_per_word = driver._bitsPerWord;
|
|
||||||
spi[0].cs_change = 0;
|
|
||||||
|
|
||||||
if (rx != NULL) {
|
|
||||||
// keep valgrind happy
|
|
||||||
memset(rx, 0, len);
|
|
||||||
}
|
|
||||||
|
|
||||||
r = ioctl(fd, SPI_IOC_MESSAGE(1), &spi);
|
|
||||||
cs_release(driver._type);
|
|
||||||
|
|
||||||
if (r == -1) {
|
|
||||||
hal.console->printf("SPI: error on doing transaction\n");
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
|
||||||
return a SPIDeviceDriver for a particular device
|
|
||||||
*/
|
|
||||||
AP_HAL::SPIDeviceDriver *SPIDeviceManager::device(enum AP_HAL::SPIDeviceType dev, uint8_t index)
|
|
||||||
{
|
|
||||||
uint8_t count = 0;
|
|
||||||
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
|
|
||||||
if (_device[i]._type == dev) {
|
|
||||||
if (count == index) {
|
|
||||||
return &_device[i];
|
|
||||||
} else {
|
|
||||||
count++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return NULL;
|
|
||||||
}
|
|
@ -1,89 +0,0 @@
|
|||||||
#pragma once
|
|
||||||
|
|
||||||
#include <vector>
|
|
||||||
|
|
||||||
#include <AP_HAL/SPIDevice.h>
|
|
||||||
#include <AP_HAL/utility/OwnPtr.h>
|
|
||||||
|
|
||||||
#include "AP_HAL_Linux.h"
|
|
||||||
#include "Semaphores.h"
|
|
||||||
|
|
||||||
#define LINUX_SPI_MAX_BUSES 3
|
|
||||||
|
|
||||||
// Fake CS pin to indicate in-kernel handling
|
|
||||||
#define SPI_CS_KERNEL -1
|
|
||||||
|
|
||||||
namespace Linux {
|
|
||||||
|
|
||||||
class SPIBus;
|
|
||||||
|
|
||||||
class SPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
|
|
||||||
public:
|
|
||||||
friend class SPIDeviceManager;
|
|
||||||
friend class SPIDevice;
|
|
||||||
|
|
||||||
SPIDeviceDriver(const char *name, uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDeviceType type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
|
|
||||||
|
|
||||||
void init();
|
|
||||||
AP_HAL::Semaphore *get_semaphore();
|
|
||||||
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
|
||||||
|
|
||||||
void cs_assert();
|
|
||||||
void cs_release();
|
|
||||||
uint8_t transfer (uint8_t data);
|
|
||||||
void transfer (const uint8_t *data, uint16_t len);
|
|
||||||
void set_bus_speed(enum bus_speed speed);
|
|
||||||
|
|
||||||
private:
|
|
||||||
uint16_t _bus;
|
|
||||||
uint16_t _subdev;
|
|
||||||
int16_t _cs_pin;
|
|
||||||
AP_HAL::DigitalSource *_cs;
|
|
||||||
const char *_name;
|
|
||||||
uint8_t _mode;
|
|
||||||
uint8_t _bitsPerWord;
|
|
||||||
uint32_t _lowspeed;
|
|
||||||
uint32_t _highspeed;
|
|
||||||
uint32_t _speed;
|
|
||||||
enum AP_HAL::SPIDeviceType _type;
|
|
||||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _fake_dev;
|
|
||||||
};
|
|
||||||
|
|
||||||
class SPIDeviceManager : public AP_HAL::SPIDeviceManager {
|
|
||||||
public:
|
|
||||||
friend class SPIDevice;
|
|
||||||
|
|
||||||
static SPIDeviceManager *from(AP_HAL::SPIDeviceManager *spi_mgr)
|
|
||||||
{
|
|
||||||
return static_cast<SPIDeviceManager*>(spi_mgr);
|
|
||||||
}
|
|
||||||
|
|
||||||
SPIDeviceManager()
|
|
||||||
{
|
|
||||||
/* Reserve space up-front for 3 buses */
|
|
||||||
_buses.reserve(3);
|
|
||||||
}
|
|
||||||
|
|
||||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name);
|
|
||||||
|
|
||||||
// Temporary function to interoperate with SPIDeviceDriver interface
|
|
||||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(SPIDeviceDriver &desc);
|
|
||||||
|
|
||||||
void init();
|
|
||||||
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDeviceType, uint8_t index = 0);
|
|
||||||
|
|
||||||
static void cs_assert(enum AP_HAL::SPIDeviceType type);
|
|
||||||
static void cs_release(enum AP_HAL::SPIDeviceType type);
|
|
||||||
static bool transaction(SPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
|
||||||
|
|
||||||
protected:
|
|
||||||
void _unregister(SPIBus &b);
|
|
||||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _create_device(SPIBus &b, SPIDeviceDriver &device_desc) const;
|
|
||||||
|
|
||||||
std::vector<SPIBus*> _buses;
|
|
||||||
|
|
||||||
static const uint8_t _n_device_desc;
|
|
||||||
static SPIDeviceDriver _device[];
|
|
||||||
};
|
|
||||||
|
|
||||||
}
|
|
Loading…
Reference in New Issue
Block a user