|
|
|
@ -1,18 +1,16 @@
@@ -1,18 +1,16 @@
|
|
|
|
|
#include "SPIUARTDriver.h" |
|
|
|
|
|
|
|
|
|
#include <assert.h> |
|
|
|
|
#include <stdlib.h> |
|
|
|
|
#include <cstdio> |
|
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
|
#include <AP_HAL/utility/RingBuffer.h> |
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
extern const AP_HAL::HAL &hal; |
|
|
|
|
|
|
|
|
|
#define SPIUART_DEBUG 0 |
|
|
|
|
|
|
|
|
|
#include <cassert> |
|
|
|
|
|
|
|
|
|
#if SPIUART_DEBUG |
|
|
|
|
#ifdef SPIUART_DEBUG |
|
|
|
|
#include <stdio.h> |
|
|
|
|
#define debug(fmt, args ...) do {hal.console->printf("[SPIUARTDriver]: %s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) |
|
|
|
|
#define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) |
|
|
|
|
#else |
|
|
|
@ -22,43 +20,21 @@ extern const AP_HAL::HAL& hal;
@@ -22,43 +20,21 @@ extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
|
|
using namespace Linux; |
|
|
|
|
|
|
|
|
|
SPIUARTDriver::SPIUARTDriver() : |
|
|
|
|
UARTDriver(false), |
|
|
|
|
_dev(nullptr), |
|
|
|
|
_last_update_timestamp(0), |
|
|
|
|
_buffer(NULL), |
|
|
|
|
_external(false) |
|
|
|
|
{ |
|
|
|
|
_readbuf = NULL; |
|
|
|
|
_writebuf = NULL; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool SPIUARTDriver::sem_take_nonblocking() |
|
|
|
|
SPIUARTDriver::SPIUARTDriver() |
|
|
|
|
: UARTDriver(false) |
|
|
|
|
{ |
|
|
|
|
return _dev->get_semaphore()->take_nonblocking(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void SPIUARTDriver::sem_give() |
|
|
|
|
{ |
|
|
|
|
_dev->get_semaphore()->give(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) |
|
|
|
|
{ |
|
|
|
|
if (device_path != NULL) { |
|
|
|
|
UARTDriver::begin(b,rxS,txS); |
|
|
|
|
if ( is_initialized()) { |
|
|
|
|
UARTDriver::begin(b, rxS, txS); |
|
|
|
|
if (is_initialized()) { |
|
|
|
|
_external = true; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (rxS < 1024) { |
|
|
|
|
rxS = 2048; |
|
|
|
|
} |
|
|
|
|
if (txS < 1024) { |
|
|
|
|
txS = 2048; |
|
|
|
|
} |
|
|
|
|
if (!is_initialized()) { |
|
|
|
|
_dev = hal.spi->get_device("ublox"); |
|
|
|
|
if (!_dev) { |
|
|
|
@ -66,6 +42,13 @@ void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
@@ -66,6 +42,13 @@ void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (rxS < 1024) { |
|
|
|
|
rxS = 2048; |
|
|
|
|
} |
|
|
|
|
if (txS < 1024) { |
|
|
|
|
txS = 2048; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
allocate the read buffer |
|
|
|
|
*/ |
|
|
|
@ -101,8 +84,6 @@ void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
@@ -101,8 +84,6 @@ void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_dev = hal.spi->get_device("ublox"); |
|
|
|
|
|
|
|
|
|
switch (b) { |
|
|
|
|
case 4000000U: |
|
|
|
|
if (is_initialized()) { |
|
|
|
@ -133,13 +114,13 @@ int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
@@ -133,13 +114,13 @@ int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
|
|
|
|
|
return UARTDriver::_write_fd(buf,size); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!sem_take_nonblocking()) { |
|
|
|
|
if (!_dev->get_semaphore()->take_nonblocking()) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_dev->transfer_fullduplex(buf, _buffer, size); |
|
|
|
|
|
|
|
|
|
sem_give(); |
|
|
|
|
_dev->get_semaphore()->give(); |
|
|
|
|
|
|
|
|
|
BUF_ADVANCEHEAD(_writebuf, size); |
|
|
|
|
|
|
|
|
@ -186,9 +167,7 @@ int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
@@ -186,9 +167,7 @@ int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
|
|
|
|
|
BUF_ADVANCETAIL(_readbuf, n); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
return ret; |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static uint8_t ff_stub[300] = {0xff}; |
|
|
|
@ -199,23 +178,21 @@ int SPIUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
@@ -199,23 +178,21 @@ int SPIUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
|
|
|
|
return UARTDriver::_read_fd(buf, n); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!sem_take_nonblocking()) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* Make SPI transactions shorter. It can save SPI bus from keeping too
|
|
|
|
|
* long. It's essential for NavIO as MPU9250 is on the same bus and |
|
|
|
|
* doesn't like to be waiting. Making transactions more frequent but shorter |
|
|
|
|
* is a win. |
|
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
if (n > 100) { |
|
|
|
|
n = 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_dev->transfer_fullduplex(ff_stub, buf, n); |
|
|
|
|
if (!_dev->get_semaphore()->take_nonblocking()) { |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
sem_give(); |
|
|
|
|
_dev->transfer_fullduplex(ff_stub, buf, n); |
|
|
|
|
_dev->get_semaphore()->give(); |
|
|
|
|
|
|
|
|
|
BUF_ADVANCETAIL(_readbuf, n); |
|
|
|
|
|
|
|
|
@ -228,6 +205,7 @@ void SPIUARTDriver::_timer_tick(void)
@@ -228,6 +205,7 @@ void SPIUARTDriver::_timer_tick(void)
|
|
|
|
|
UARTDriver::_timer_tick(); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* lower the update rate */ |
|
|
|
|
if (AP_HAL::micros() - _last_update_timestamp < 10000) { |
|
|
|
|
return; |
|
|
|
|