ardupilot/libraries/AP_HAL_Linux/RPIOUARTDriver.cpp

279 lines
6.7 KiB
C++
Raw Normal View History

#include "RPIOUARTDriver.h"
2015-08-18 00:29:58 -03:00
#include <stdlib.h>
#include <cstdio>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/RingBuffer.h>
2015-08-18 00:29:58 -03:00
#include "px4io_protocol.h"
#define RPIOUART_POLL_TIME_INTERVAL 10000
extern const AP_HAL::HAL& hal;
#define RPIOUART_DEBUG 0
#include <cassert>
#if RPIOUART_DEBUG
#define debug(fmt, args ...) do {hal.console->printf("[RPIOUARTDriver]: %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
#define debug(fmt, args ...)
#define error(fmt, args ...)
2015-08-18 00:29:58 -03:00
#endif
using namespace Linux;
RPIOUARTDriver::RPIOUARTDriver() :
UARTDriver(false),
_dev(nullptr),
2015-08-18 00:29:58 -03:00
_last_update_timestamp(0),
_external(false),
_need_set_baud(false),
_baudrate(0)
{
_readbuf = NULL;
_writebuf = NULL;
}
bool RPIOUARTDriver::sem_take_nonblocking()
2015-08-18 00:29:58 -03:00
{
return _dev->get_semaphore()->take_nonblocking();
2015-08-18 00:29:58 -03:00
}
void RPIOUARTDriver::sem_give()
2015-08-18 00:29:58 -03:00
{
_dev->get_semaphore()->give();
2015-08-18 00:29:58 -03:00
}
bool RPIOUARTDriver::isExternal()
2015-08-18 00:29:58 -03:00
{
return _external;
}
void RPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
2015-08-18 00:29:58 -03:00
{
//hal.console->printf("[RPIOUARTDriver]: begin \n");
2015-08-18 00:29:58 -03:00
if (device_path != NULL) {
UARTDriver::begin(b,rxS,txS);
2015-08-18 00:29:58 -03:00
if ( is_initialized()) {
_external = true;
return;
}
}
if (rxS < 1024) {
rxS = 2048;
}
if (txS < 1024) {
txS = 2048;
}
2015-08-18 00:29:58 -03:00
_initialised = false;
while (_in_timer) hal.scheduler->delay(1);
/*
allocate the read buffer
*/
if (rxS != 0 && rxS != _readbuf_size) {
_readbuf_size = rxS;
if (_readbuf != NULL) {
free(_readbuf);
}
_readbuf = (uint8_t *)malloc(_readbuf_size);
_readbuf_head = 0;
_readbuf_tail = 0;
}
/*
allocate the write buffer
*/
if (txS != 0 && txS != _writebuf_size) {
_writebuf_size = txS;
if (_writebuf != NULL) {
free(_writebuf);
}
_writebuf = (uint8_t *)malloc(_writebuf_size);
_writebuf_head = 0;
_writebuf_tail = 0;
}
_dev = hal.spi->get_device("raspio");
2015-08-18 00:29:58 -03:00
/* set baudrate */
_baudrate = b;
_need_set_baud = true;
while (_need_set_baud) {
hal.scheduler->delay(1);
}
if (_writebuf_size != 0 && _readbuf_size != 0) {
_initialised = true;
}
}
int RPIOUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
2015-08-18 00:29:58 -03:00
{
if (_external) {
return UARTDriver::_write_fd(buf, n);
}
2015-08-18 00:29:58 -03:00
return -1;
}
int RPIOUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
2015-08-18 00:29:58 -03:00
{
if (_external) {
return UARTDriver::_read_fd(buf, n);
2015-08-18 00:29:58 -03:00
}
2015-08-18 00:29:58 -03:00
return -1;
}
void RPIOUARTDriver::_timer_tick(void)
2015-08-18 00:29:58 -03:00
{
if (_external) {
UARTDriver::_timer_tick();
2015-08-18 00:29:58 -03:00
return;
}
2015-08-18 00:29:58 -03:00
/* set the baudrate of raspilotio */
if (_need_set_baud) {
2015-08-18 00:29:58 -03:00
if (_baudrate != 0) {
if (!_dev->get_semaphore()->take_nonblocking()) {
2015-08-18 00:29:58 -03:00
return;
}
2015-08-18 00:29:58 -03:00
struct IOPacket _dma_packet_tx, _dma_packet_rx;
2015-08-18 00:29:58 -03:00
_dma_packet_tx.count_code = 2 | PKT_CODE_WRITE;
_dma_packet_tx.page = PX4IO_PAGE_UART_BUFFER;
_dma_packet_tx.offset = 0;
_dma_packet_tx.regs[0] = _baudrate & 0xffff;
_dma_packet_tx.regs[1] = _baudrate >> 16;
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
_dev->transfer((uint8_t *)&_dma_packet_tx, sizeof(_dma_packet_tx),
(uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_rx));
2015-08-18 00:29:58 -03:00
hal.scheduler->delay(1);
_dev->get_semaphore()->give();
2015-08-18 00:29:58 -03:00
}
2015-08-18 00:29:58 -03:00
_need_set_baud = false;
}
/* finish set */
2015-08-18 00:29:58 -03:00
if (!_initialised) return;
2015-08-18 00:29:58 -03:00
/* lower the update rate */
if (AP_HAL::micros() - _last_update_timestamp < RPIOUART_POLL_TIME_INTERVAL) {
2015-08-18 00:29:58 -03:00
return;
}
2015-08-18 00:29:58 -03:00
_in_timer = true;
if (!_dev->get_semaphore()->take_nonblocking()) {
2015-08-18 00:29:58 -03:00
return;
}
2015-08-18 00:29:58 -03:00
struct IOPacket _dma_packet_tx, _dma_packet_rx;
2015-08-18 00:29:58 -03:00
/* get write_buf bytes */
uint16_t _tail;
uint16_t n = BUF_AVAILABLE(_writebuf);
2015-08-18 00:29:58 -03:00
if (n > PKT_MAX_REGS * 2) {
n = PKT_MAX_REGS * 2;
}
2015-08-18 00:29:58 -03:00
uint16_t _max_size = _baudrate / 10 / (1000000 / RPIOUART_POLL_TIME_INTERVAL);
if (n > _max_size) {
n = _max_size;
}
2015-08-18 00:29:58 -03:00
if (n > 0) {
uint16_t n1 = _writebuf_size - _writebuf_head;
if (n1 >= n) {
// do as a single write
memcpy( &((uint8_t *)_dma_packet_tx.regs)[0], &_writebuf[_writebuf_head], n );
} else {
// split into two writes
memcpy( &((uint8_t *)_dma_packet_tx.regs)[0], &_writebuf[_writebuf_head], n1 );
memcpy( &((uint8_t *)_dma_packet_tx.regs)[n1], &_writebuf[0], n-n1 );
}
2015-08-18 00:29:58 -03:00
BUF_ADVANCEHEAD(_writebuf, n);
}
2015-08-18 00:29:58 -03:00
_dma_packet_tx.count_code = PKT_MAX_REGS | PKT_CODE_SPIUART;
_dma_packet_tx.page = PX4IO_PAGE_UART_BUFFER;
_dma_packet_tx.offset = n;
/* end get write_buf bytes */
2015-08-18 00:29:58 -03:00
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
/* set raspilotio to read uart data */
_dev->transfer((uint8_t *)&_dma_packet_tx, sizeof(_dma_packet_tx),
(uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_rx));
2015-08-18 00:29:58 -03:00
hal.scheduler->delay_microseconds(100);
2015-08-18 00:29:58 -03:00
/* get uart data from raspilotio */
_dma_packet_tx.count_code = 0 | PKT_CODE_READ;
_dma_packet_tx.page = 0;
_dma_packet_tx.offset = 0;
memset( &_dma_packet_tx.regs[0], 0, PKT_MAX_REGS*sizeof(uint16_t) );
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
_dev->transfer((uint8_t *)&_dma_packet_tx, sizeof(_dma_packet_tx),
(uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_rx));
2015-08-18 00:29:58 -03:00
hal.scheduler->delay_microseconds(100);
2015-08-18 00:29:58 -03:00
/* release sem */
_dev->get_semaphore()->give();
2015-08-18 00:29:58 -03:00
/* add bytes to read buf */
uint16_t _head;
n = BUF_SPACE(_readbuf);
2015-08-18 00:29:58 -03:00
if (_dma_packet_rx.page == PX4IO_PAGE_UART_BUFFER) {
2015-08-18 00:29:58 -03:00
if (n > _dma_packet_rx.offset) {
n = _dma_packet_rx.offset;
}
2015-08-18 00:29:58 -03:00
if (n > PKT_MAX_REGS * 2) {
n = PKT_MAX_REGS * 2;
}
2015-08-18 00:29:58 -03:00
if (n > 0) {
uint16_t n1 = _readbuf_size - _readbuf_tail;
if (n1 >= n) {
// one read will do
memcpy( &_readbuf[_readbuf_tail], &((uint8_t *)_dma_packet_rx.regs)[0], n );
} else {
memcpy( &_readbuf[_readbuf_tail], &((uint8_t *)_dma_packet_rx.regs)[0], n1 );
memcpy( &_readbuf[0], &((uint8_t *)_dma_packet_rx.regs)[n1], n-n1 );
}
2015-08-18 00:29:58 -03:00
BUF_ADVANCETAIL(_readbuf, n);
}
2015-08-18 00:29:58 -03:00
}
2015-08-18 00:29:58 -03:00
_in_timer = false;
_last_update_timestamp = AP_HAL::micros();
2015-08-18 00:29:58 -03:00
}