HAL_Linux: added SPI support

This commit is contained in:
Andrew Tridgell 2013-09-29 00:51:43 +10:00
parent 9679faae3b
commit 884af71ef6
3 changed files with 180 additions and 11 deletions

View File

@ -4,9 +4,6 @@
#include "HAL_Linux_Class.h"
#include "AP_HAL_Linux_Private.h"
#include <AP_HAL_Empty.h>
#include <AP_HAL_Empty_Private.h>
#include <getopt.h>
#include <stdio.h>
#include <unistd.h>
@ -14,14 +11,14 @@
using namespace Linux;
// only using 2 serial ports on Linux for now
// 3 serial ports on Linux for now
static LinuxUARTDriver uartADriver;
static LinuxUARTDriver uartBDriver;
static Empty::EmptyUARTDriver uartCDriver;
static LinuxUARTDriver uartCDriver;
static LinuxSemaphore i2cSemaphore;
static LinuxI2CDriver i2cDriver(&i2cSemaphore, "/dev/i2c-1");
static Empty::EmptySPIDeviceManager spiDeviceManager;
static LinuxSPIDeviceManager spiDeviceManager;
static LinuxAnalogIn analogIn;
static LinuxStorage storageDriver;
static LinuxConsoleDriver consoleDriver(&uartADriver);
@ -54,7 +51,7 @@ void HAL_Linux::init(int argc,char* const argv[]) const
/*
parse command line options
*/
while ((opt = getopt(argc, argv, "A:B:h")) != -1) {
while ((opt = getopt(argc, argv, "A:B:C:h")) != -1) {
switch (opt) {
case 'A':
uartADriver.set_device_path(optarg);
@ -62,8 +59,11 @@ void HAL_Linux::init(int argc,char* const argv[]) const
case 'B':
uartBDriver.set_device_path(optarg);
break;
case 'C':
uartCDriver.set_device_path(optarg);
break;
case 'h':
printf("Usage: -A uartAPath -B uartAPath\n");
printf("Usage: -A uartAPath -B uartBPath -C uartCPath\n");
exit(0);
default:
printf("Unknown option '%c'\n", (char)opt);
@ -71,12 +71,10 @@ void HAL_Linux::init(int argc,char* const argv[]) const
}
}
/* initialize all drivers and private members here.
* up to the programmer to do this in the correct order.
* Scheduler should likely come first. */
scheduler->init(NULL);
uartA->begin(115200);
i2c->begin();
spi->init(NULL);
}
const HAL_Linux AP_HAL_Linux;

View File

@ -0,0 +1,133 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include "SPIDriver.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
#include <stdint.h>
#include <sys/ioctl.h>
#include <linux/spi/spidev.h>
using namespace Linux;
LinuxSPIDeviceDriver::LinuxSPIDeviceDriver(const char *spipath, uint8_t mode, uint8_t bitsPerWord, uint32_t speed) :
_spipath(spipath),
_fd(-1),
_mode(mode),
_bitsPerWord(bitsPerWord),
_speed(speed)
{}
void LinuxSPIDeviceDriver::init()
{
_fd = open(_spipath, O_RDWR);
if (_fd == -1) {
return;
}
int ret;
ret = ioctl(_fd, SPI_IOC_WR_MODE, &_mode);
if (ret == -1) {
goto failed;
}
ret = ioctl(_fd, SPI_IOC_RD_MODE, &_mode);
if (ret == -1) {
goto failed;
}
ret = ioctl(_fd, SPI_IOC_WR_BITS_PER_WORD, &_bitsPerWord);
if (ret == -1) {
goto failed;
}
ret = ioctl(_fd, SPI_IOC_RD_BITS_PER_WORD, &_bitsPerWord);
if (ret == -1) {
goto failed;
}
ret = ioctl(_fd, SPI_IOC_WR_MAX_SPEED_HZ, &_speed);
if (ret == -1) {
goto failed;
}
ret = ioctl(_fd, SPI_IOC_RD_MAX_SPEED_HZ, &_speed);
if (ret == -1) {
goto failed;
}
return;
failed:
close(_fd);
_fd = -1;
}
AP_HAL::Semaphore* LinuxSPIDeviceDriver::get_semaphore()
{
return &_semaphore;
}
void LinuxSPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
{
struct spi_ioc_transfer spi[len];
for (uint8_t i = 0; i < len ; i++) {
spi[i].tx_buf = tx?(uint64_t)(tx + i):NULL;
spi[i].rx_buf = rx?(uint64_t)(rx + i):NULL;
spi[i].len = 1;
spi[i].delay_usecs = 0;
spi[i].speed_hz = _speed;
spi[i].bits_per_word = _bitsPerWord;
spi[i].cs_change = 0;
}
ioctl(_fd, SPI_IOC_MESSAGE(len), &spi);
}
void LinuxSPIDeviceDriver::cs_assert()
{
}
void LinuxSPIDeviceDriver::cs_release()
{
}
uint8_t LinuxSPIDeviceDriver::transfer(uint8_t data)
{
uint8_t v = 0;
transaction(&data, &v, 1);
return v;
}
void LinuxSPIDeviceDriver::transfer(const uint8_t *data, uint16_t len)
{
transaction(data, NULL, len);
}
LinuxSPIDeviceManager::LinuxSPIDeviceManager() :
_device_cs0("/dev/spidev0.0", SPI_MODE_0, 8, 2600000),
_device_cs1("/dev/spidev0.1", SPI_MODE_0, 8, 1000000)
{}
void LinuxSPIDeviceManager::init(void *)
{
_device_cs0.init();
_device_cs1.init();
}
/*
return a SPIDeviceDriver for a particular device
*/
AP_HAL::SPIDeviceDriver* LinuxSPIDeviceManager::device(enum AP_HAL::SPIDevice dev)
{
switch (dev) {
case AP_HAL::SPIDevice_ADS7844:
return &_device_cs0;
}
return NULL;
}
#endif // CONFIG_HAL_BOARD

View File

@ -0,0 +1,38 @@
#ifndef __AP_HAL_EMPTY_SPIDRIVER_H__
#define __AP_HAL_EMPTY_SPIDRIVER_H__
#include <AP_HAL_Linux.h>
#include "Semaphores.h"
class Linux::LinuxSPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
public:
LinuxSPIDeviceDriver(const char *spipath, uint8_t mode, uint8_t bitsPerWord, uint32_t speed);
void init();
AP_HAL::Semaphore* get_semaphore();
void 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);
private:
LinuxSemaphore _semaphore;
const char *_spipath;
int _fd;
uint8_t _mode;
uint8_t _bitsPerWord;
uint32_t _speed;
};
class Linux::LinuxSPIDeviceManager : public AP_HAL::SPIDeviceManager {
public:
LinuxSPIDeviceManager();
void init(void *);
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice);
private:
LinuxSPIDeviceDriver _device_cs0;
LinuxSPIDeviceDriver _device_cs1;
};
#endif // __AP_HAL_LINUX_SPIDRIVER_H__