2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-01-02 20:03:05 -04:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
#include "UARTDriver.h"
|
2013-01-03 02:27:53 -04:00
|
|
|
|
2013-01-02 20:03:05 -04:00
|
|
|
#include <stdio.h>
|
|
|
|
#include <unistd.h>
|
2013-01-03 02:27:53 -04:00
|
|
|
#include <stdlib.h>
|
2013-01-03 06:12:10 -04:00
|
|
|
#include <errno.h>
|
|
|
|
#include <sys/ioctl.h>
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <fcntl.h>
|
2013-01-04 04:42:30 -04:00
|
|
|
#include <termios.h>
|
2013-02-18 21:02:46 -04:00
|
|
|
#include <drivers/drv_hrt.h>
|
2013-02-20 03:15:56 -04:00
|
|
|
#include <assert.h>
|
2015-08-10 22:40:32 -03:00
|
|
|
#include "GPIO.h"
|
2013-01-02 20:03:05 -04:00
|
|
|
|
|
|
|
using namespace PX4;
|
|
|
|
|
2013-01-03 06:12:10 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2013-01-24 00:01:48 -04:00
|
|
|
PX4UARTDriver::PX4UARTDriver(const char *devpath, const char *perf_name) :
|
|
|
|
_devpath(devpath),
|
2013-10-05 02:47:28 -03:00
|
|
|
_fd(-1),
|
|
|
|
_baudrate(57600),
|
|
|
|
_initialised(false),
|
2014-02-10 20:22:08 -04:00
|
|
|
_in_timer(false),
|
2017-12-08 22:29:25 -04:00
|
|
|
_unbuffered_writes(false),
|
2015-04-24 02:12:33 -03:00
|
|
|
_perf_uart(perf_alloc(PC_ELAPSED, perf_name)),
|
2015-07-13 20:52:48 -03:00
|
|
|
_os_start_auto_space(-1),
|
2017-12-08 22:29:25 -04:00
|
|
|
_flow_control(FLOW_CONTROL_DISABLE)
|
2013-10-05 02:47:28 -03:00
|
|
|
{
|
|
|
|
}
|
2013-01-24 00:01:48 -04:00
|
|
|
|
2013-01-02 20:03:05 -04:00
|
|
|
|
2013-01-03 02:27:53 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2013-01-02 20:03:05 -04:00
|
|
|
/*
|
2013-01-04 04:42:30 -04:00
|
|
|
this UART driver maps to a serial device in /dev
|
2013-01-02 20:03:05 -04:00
|
|
|
*/
|
|
|
|
|
2016-10-05 13:11:26 -03:00
|
|
|
void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
2013-01-04 04:42:30 -04:00
|
|
|
{
|
2013-11-22 04:16:51 -04:00
|
|
|
if (strcmp(_devpath, "/dev/null") == 0) {
|
|
|
|
// leave uninitialised
|
|
|
|
return;
|
|
|
|
}
|
2013-12-27 23:24:06 -04:00
|
|
|
|
2014-02-10 20:22:08 -04:00
|
|
|
uint16_t min_tx_buffer = 1024;
|
2013-12-27 23:24:06 -04:00
|
|
|
uint16_t min_rx_buffer = 512;
|
|
|
|
if (strcmp(_devpath, "/dev/ttyACM0") == 0) {
|
2018-05-15 21:42:49 -03:00
|
|
|
_is_usb = true;
|
2015-03-27 19:08:52 -03:00
|
|
|
min_tx_buffer = 4096;
|
2013-12-27 23:24:06 -04:00
|
|
|
min_rx_buffer = 1024;
|
|
|
|
}
|
2013-10-05 02:47:28 -03:00
|
|
|
// on PX4 we have enough memory to have a larger transmit and
|
|
|
|
// receive buffer for all ports. This means we don't get delays
|
|
|
|
// while waiting to write GPS config packets
|
2013-12-27 23:24:06 -04:00
|
|
|
if (txS < min_tx_buffer) {
|
|
|
|
txS = min_tx_buffer;
|
2013-10-05 02:47:28 -03:00
|
|
|
}
|
2013-12-27 23:24:06 -04:00
|
|
|
if (rxS < min_rx_buffer) {
|
|
|
|
rxS = min_rx_buffer;
|
2013-10-05 02:47:28 -03:00
|
|
|
}
|
2013-01-22 05:11:12 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
allocate the read buffer
|
2013-10-05 02:47:28 -03:00
|
|
|
we allocate buffers before we successfully open the device as we
|
|
|
|
want to allocate in the early stages of boot, and cause minimum
|
|
|
|
thrashing of the heap once we are up. The ttyACM0 driver may not
|
|
|
|
connect for some time after boot
|
2013-01-22 05:11:12 -04:00
|
|
|
*/
|
2018-06-20 06:00:52 -03:00
|
|
|
while (_in_timer) {
|
|
|
|
hal.scheduler->delay(1);
|
|
|
|
}
|
2016-11-26 11:40:19 -04:00
|
|
|
if (rxS != _readbuf.get_size()) {
|
2013-10-05 02:47:28 -03:00
|
|
|
_initialised = false;
|
2016-07-30 08:54:37 -03:00
|
|
|
_readbuf.set_size(rxS);
|
|
|
|
}
|
2013-01-22 05:11:12 -04:00
|
|
|
|
2018-07-11 20:01:37 -03:00
|
|
|
bool clear_buffers = false;
|
2013-10-05 02:47:28 -03:00
|
|
|
if (b != 0) {
|
2018-07-11 20:01:37 -03:00
|
|
|
// clear buffers on baudrate change, but not on the console (which is usually USB)
|
|
|
|
if (_baudrate != b && hal.console != this) {
|
|
|
|
clear_buffers = true;
|
|
|
|
}
|
2013-10-05 02:47:28 -03:00
|
|
|
_baudrate = b;
|
|
|
|
}
|
|
|
|
|
2018-07-11 20:01:37 -03:00
|
|
|
if (clear_buffers) {
|
|
|
|
_readbuf.clear();
|
|
|
|
}
|
|
|
|
|
2013-01-22 05:11:12 -04:00
|
|
|
/*
|
|
|
|
allocate the write buffer
|
|
|
|
*/
|
2018-06-20 06:00:52 -03:00
|
|
|
while (_in_timer) {
|
|
|
|
hal.scheduler->delay(1);
|
|
|
|
}
|
2016-11-26 11:40:19 -04:00
|
|
|
if (txS != _writebuf.get_size()) {
|
2013-10-05 02:47:28 -03:00
|
|
|
_initialised = false;
|
2016-10-05 12:59:36 -03:00
|
|
|
_writebuf.set_size(txS);
|
2016-07-30 08:54:37 -03:00
|
|
|
}
|
2018-07-11 20:01:37 -03:00
|
|
|
|
|
|
|
if (clear_buffers) {
|
2018-06-20 06:00:52 -03:00
|
|
|
_writebuf.clear();
|
|
|
|
}
|
2013-02-20 03:15:56 -04:00
|
|
|
|
2013-10-05 02:47:28 -03:00
|
|
|
if (_fd == -1) {
|
|
|
|
_fd = open(_devpath, O_RDWR);
|
|
|
|
if (_fd == -1) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_baudrate != 0) {
|
|
|
|
// set the baud rate
|
|
|
|
struct termios t;
|
|
|
|
tcgetattr(_fd, &t);
|
|
|
|
cfsetspeed(&t, _baudrate);
|
|
|
|
// disable LF -> CR/LF
|
|
|
|
t.c_oflag &= ~ONLCR;
|
|
|
|
tcsetattr(_fd, TCSANOW, &t);
|
2014-02-12 02:47:23 -04:00
|
|
|
|
|
|
|
// separately setup IFLOW if we can. We do this as a 2nd call
|
|
|
|
// as if the port has no RTS pin then the tcsetattr() call
|
|
|
|
// will fail, and if done as one call then it would fail to
|
|
|
|
// set the baudrate.
|
|
|
|
tcgetattr(_fd, &t);
|
|
|
|
t.c_cflag |= CRTS_IFLOW;
|
|
|
|
tcsetattr(_fd, TCSANOW, &t);
|
2013-10-05 02:47:28 -03:00
|
|
|
}
|
|
|
|
|
2016-07-30 08:54:37 -03:00
|
|
|
if (_writebuf.get_size() && _readbuf.get_size() && _fd != -1) {
|
2013-10-12 22:43:25 -03:00
|
|
|
if (!_initialised) {
|
2018-05-15 21:42:49 -03:00
|
|
|
if (_is_usb) {
|
2015-08-10 22:40:32 -03:00
|
|
|
((PX4GPIO *)hal.gpio)->set_usb_connected();
|
|
|
|
}
|
2016-10-05 13:11:26 -03:00
|
|
|
::printf("initialised %s OK %u %u\n", _devpath,
|
2016-07-30 08:54:37 -03:00
|
|
|
(unsigned)_writebuf.get_size(), (unsigned)_readbuf.get_size());
|
2013-10-12 22:43:25 -03:00
|
|
|
}
|
2013-02-20 03:15:56 -04:00
|
|
|
_initialised = true;
|
|
|
|
}
|
2013-01-03 02:27:53 -04:00
|
|
|
}
|
|
|
|
|
2015-01-05 17:36:28 -04:00
|
|
|
void PX4UARTDriver::set_flow_control(enum flow_control fcontrol)
|
2014-02-09 21:54:50 -04:00
|
|
|
{
|
|
|
|
if (_fd == -1) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
struct termios t;
|
|
|
|
tcgetattr(_fd, &t);
|
|
|
|
// we already enabled CRTS_IFLOW above, just enable output flow control
|
2015-01-05 17:36:28 -04:00
|
|
|
if (fcontrol != FLOW_CONTROL_DISABLE) {
|
2014-02-12 02:47:23 -04:00
|
|
|
t.c_cflag |= CRTSCTS;
|
2014-02-09 21:54:50 -04:00
|
|
|
} else {
|
2014-02-12 02:47:23 -04:00
|
|
|
t.c_cflag &= ~CRTSCTS;
|
2014-02-09 21:54:50 -04:00
|
|
|
}
|
|
|
|
tcsetattr(_fd, TCSANOW, &t);
|
2015-07-13 20:52:48 -03:00
|
|
|
if (fcontrol == FLOW_CONTROL_AUTO) {
|
|
|
|
// reset flow control auto state machine
|
|
|
|
_total_written = 0;
|
|
|
|
_first_write_time = 0;
|
|
|
|
}
|
2015-01-05 17:36:28 -04:00
|
|
|
_flow_control = fcontrol;
|
2014-02-09 21:54:50 -04:00
|
|
|
}
|
|
|
|
|
2017-11-22 13:39:05 -04:00
|
|
|
void PX4UARTDriver::configure_parity(uint8_t v) {
|
|
|
|
if (_fd == -1) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
struct termios t;
|
|
|
|
tcgetattr(_fd, &t);
|
|
|
|
if (v != 0) {
|
|
|
|
// enable parity
|
|
|
|
t.c_cflag |= PARENB;
|
|
|
|
if (v == 1) {
|
|
|
|
t.c_cflag |= PARODD;
|
|
|
|
} else {
|
|
|
|
t.c_cflag &= ~PARODD;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
else {
|
|
|
|
// disable parity
|
|
|
|
t.c_cflag &= ~PARENB;
|
|
|
|
}
|
|
|
|
tcsetattr(_fd, TCSANOW, &t);
|
|
|
|
}
|
|
|
|
|
|
|
|
void PX4UARTDriver::set_stop_bits(int n) {
|
|
|
|
if (_fd == -1) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
struct termios t;
|
|
|
|
tcgetattr(_fd, &t);
|
|
|
|
if (n > 1) t.c_cflag |= CSTOPB;
|
|
|
|
else t.c_cflag &= ~CSTOPB;
|
|
|
|
tcsetattr(_fd, TCSANOW, &t);
|
|
|
|
}
|
|
|
|
|
|
|
|
bool PX4UARTDriver::set_unbuffered_writes(bool on) {
|
|
|
|
_unbuffered_writes = on;
|
|
|
|
return _unbuffered_writes;
|
|
|
|
}
|
|
|
|
|
2016-10-05 13:11:26 -03:00
|
|
|
void PX4UARTDriver::begin(uint32_t b)
|
2013-01-04 04:42:30 -04:00
|
|
|
{
|
2013-01-03 02:27:53 -04:00
|
|
|
begin(b, 0, 0);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2013-10-05 02:47:28 -03:00
|
|
|
/*
|
|
|
|
try to initialise the UART. This is used to cope with the way NuttX
|
|
|
|
handles /dev/ttyACM0 (the USB port). The port appears in /dev on
|
|
|
|
boot, but cannot be opened until a USB cable is connected and the
|
|
|
|
host starts the CDCACM communication.
|
|
|
|
*/
|
|
|
|
void PX4UARTDriver::try_initialise(void)
|
|
|
|
{
|
|
|
|
if (_initialised) {
|
|
|
|
return;
|
|
|
|
}
|
2015-11-19 23:11:07 -04:00
|
|
|
if ((AP_HAL::millis() - _last_initialise_attempt_ms) < 2000) {
|
2013-10-05 02:47:28 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-11-19 23:11:07 -04:00
|
|
|
_last_initialise_attempt_ms = AP_HAL::millis();
|
2015-01-28 19:56:52 -04:00
|
|
|
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED || !hal.util->get_soft_armed()) {
|
2013-10-05 02:47:28 -03:00
|
|
|
begin(0);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-10-05 13:11:26 -03:00
|
|
|
void PX4UARTDriver::end()
|
2013-09-28 21:14:11 -03:00
|
|
|
{
|
|
|
|
_initialised = false;
|
|
|
|
while (_in_timer) hal.scheduler->delay(1);
|
|
|
|
if (_fd != -1) {
|
|
|
|
close(_fd);
|
|
|
|
_fd = -1;
|
|
|
|
}
|
2016-07-30 08:54:37 -03:00
|
|
|
|
|
|
|
_readbuf.set_size(0);
|
|
|
|
_writebuf.set_size(0);
|
2013-09-28 21:14:11 -03:00
|
|
|
}
|
|
|
|
|
2013-01-02 20:03:05 -04:00
|
|
|
void PX4UARTDriver::flush() {}
|
2013-09-28 21:14:11 -03:00
|
|
|
|
2016-10-05 13:11:26 -03:00
|
|
|
bool PX4UARTDriver::is_initialized()
|
|
|
|
{
|
2013-10-05 02:47:28 -03:00
|
|
|
try_initialise();
|
2016-10-05 13:11:26 -03:00
|
|
|
return _initialised;
|
2013-09-28 21:14:11 -03:00
|
|
|
}
|
|
|
|
|
2016-10-05 13:11:26 -03:00
|
|
|
void PX4UARTDriver::set_blocking_writes(bool blocking)
|
2013-01-21 19:50:26 -04:00
|
|
|
{
|
2013-01-22 06:52:21 -04:00
|
|
|
_nonblocking_writes = !blocking;
|
2013-01-03 06:12:10 -04:00
|
|
|
}
|
2013-09-28 21:14:11 -03:00
|
|
|
|
2013-01-02 20:03:05 -04:00
|
|
|
bool PX4UARTDriver::tx_pending() { return false; }
|
|
|
|
|
2013-01-22 05:11:12 -04:00
|
|
|
/*
|
|
|
|
return number of bytes available to be read from the buffer
|
|
|
|
*/
|
2016-08-02 10:42:50 -03:00
|
|
|
uint32_t PX4UARTDriver::available()
|
2016-07-30 08:54:37 -03:00
|
|
|
{
|
|
|
|
if (!_initialised) {
|
2013-10-05 02:47:28 -03:00
|
|
|
try_initialise();
|
2016-07-30 08:54:37 -03:00
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
return _readbuf.available();
|
2013-01-03 02:27:53 -04:00
|
|
|
}
|
|
|
|
|
2013-01-22 05:11:12 -04:00
|
|
|
/*
|
|
|
|
return number of bytes that can be added to the write buffer
|
|
|
|
*/
|
2016-08-02 10:42:50 -03:00
|
|
|
uint32_t PX4UARTDriver::txspace()
|
2016-07-30 08:54:37 -03:00
|
|
|
{
|
|
|
|
if (!_initialised) {
|
2013-10-05 02:47:28 -03:00
|
|
|
try_initialise();
|
2016-07-30 08:54:37 -03:00
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
return _writebuf.space();
|
2013-01-03 02:27:53 -04:00
|
|
|
}
|
2013-01-02 20:03:05 -04:00
|
|
|
|
2013-01-22 05:11:12 -04:00
|
|
|
/*
|
|
|
|
read one byte from the read buffer
|
|
|
|
*/
|
2016-07-30 08:54:37 -03:00
|
|
|
int16_t PX4UARTDriver::read()
|
|
|
|
{
|
2017-09-25 19:03:35 -03:00
|
|
|
if (!_semaphore.take_nonblocking()) {
|
2014-09-06 13:24:41 -03:00
|
|
|
return -1;
|
|
|
|
}
|
2013-10-05 02:47:28 -03:00
|
|
|
if (!_initialised) {
|
|
|
|
try_initialise();
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
2013-10-05 02:47:28 -03:00
|
|
|
return -1;
|
|
|
|
}
|
2016-07-30 08:54:37 -03:00
|
|
|
|
|
|
|
uint8_t byte;
|
|
|
|
if (!_readbuf.read_byte(&byte)) {
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
2013-01-22 05:11:12 -04:00
|
|
|
return -1;
|
|
|
|
}
|
2016-07-30 08:54:37 -03:00
|
|
|
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
2016-07-30 08:54:37 -03:00
|
|
|
return byte;
|
2013-01-02 20:03:05 -04:00
|
|
|
}
|
|
|
|
|
2016-10-05 13:11:26 -03:00
|
|
|
/*
|
2017-11-22 13:39:05 -04:00
|
|
|
write one byte
|
2013-01-22 05:11:12 -04:00
|
|
|
*/
|
2016-10-05 13:11:26 -03:00
|
|
|
size_t PX4UARTDriver::write(uint8_t c)
|
|
|
|
{
|
2017-09-25 19:03:35 -03:00
|
|
|
if (!_semaphore.take_nonblocking()) {
|
|
|
|
return -1;
|
2013-01-21 19:50:26 -04:00
|
|
|
}
|
2014-09-06 13:24:41 -03:00
|
|
|
if (!_initialised) {
|
|
|
|
try_initialise();
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
2013-01-22 18:22:51 -04:00
|
|
|
return 0;
|
|
|
|
}
|
2013-02-18 21:02:46 -04:00
|
|
|
|
2017-11-22 13:39:05 -04:00
|
|
|
if (_unbuffered_writes) {
|
|
|
|
// write one byte to the file descriptor
|
|
|
|
return _write_fd(&c, 1);
|
|
|
|
}
|
|
|
|
|
2016-07-30 08:54:37 -03:00
|
|
|
while (_writebuf.space() == 0) {
|
2013-01-22 06:52:21 -04:00
|
|
|
if (_nonblocking_writes) {
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
2013-01-22 06:52:21 -04:00
|
|
|
return 0;
|
|
|
|
}
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
2013-01-22 06:52:21 -04:00
|
|
|
hal.scheduler->delay(1);
|
2017-09-25 19:03:35 -03:00
|
|
|
if (!_semaphore.take_nonblocking()) {
|
|
|
|
return -1;
|
|
|
|
}
|
2013-01-22 06:52:21 -04:00
|
|
|
}
|
2017-09-25 19:03:35 -03:00
|
|
|
size_t ret = _writebuf.write(&c, 1);
|
|
|
|
_semaphore.give();
|
|
|
|
return ret;
|
2013-01-21 19:50:26 -04:00
|
|
|
}
|
|
|
|
|
2013-01-22 05:11:12 -04:00
|
|
|
/*
|
2017-11-22 13:39:05 -04:00
|
|
|
* write size bytes
|
2013-01-22 05:11:12 -04:00
|
|
|
*/
|
2013-01-21 19:50:26 -04:00
|
|
|
size_t PX4UARTDriver::write(const uint8_t *buffer, size_t size)
|
|
|
|
{
|
2017-09-25 19:03:35 -03:00
|
|
|
if (!_semaphore.take_nonblocking()) {
|
|
|
|
return -1;
|
2014-09-06 13:24:41 -03:00
|
|
|
}
|
2017-11-22 13:39:05 -04:00
|
|
|
if (!_initialised) {
|
2013-10-05 02:47:28 -03:00
|
|
|
try_initialise();
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
|
|
|
return 0;
|
|
|
|
}
|
2013-03-20 01:41:52 -03:00
|
|
|
|
2017-09-25 19:03:35 -03:00
|
|
|
size_t ret = 0;
|
|
|
|
|
2013-03-20 01:41:52 -03:00
|
|
|
if (!_nonblocking_writes) {
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
2013-03-20 01:41:52 -03:00
|
|
|
/*
|
|
|
|
use the per-byte delay loop in write() above for blocking writes
|
|
|
|
*/
|
|
|
|
while (size--) {
|
|
|
|
if (write(*buffer++) != 1) break;
|
|
|
|
ret++;
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2017-11-22 13:39:05 -04:00
|
|
|
if (_unbuffered_writes) {
|
|
|
|
// write buffer straight to the file descriptor
|
2017-09-25 19:03:35 -03:00
|
|
|
ret = _write_fd(buffer, size);
|
|
|
|
} else {
|
|
|
|
ret = _writebuf.write(buffer, size);
|
2017-11-22 13:39:05 -04:00
|
|
|
}
|
2017-09-25 19:03:35 -03:00
|
|
|
_semaphore.give();
|
|
|
|
return ret;
|
2013-01-02 22:16:41 -04:00
|
|
|
}
|
|
|
|
|
2013-02-18 21:02:46 -04:00
|
|
|
/*
|
|
|
|
try writing n bytes, handling an unresponsive port
|
|
|
|
*/
|
|
|
|
int PX4UARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
|
|
|
{
|
|
|
|
int ret = 0;
|
|
|
|
|
|
|
|
// the FIONWRITE check is to cope with broken O_NONBLOCK behaviour
|
|
|
|
// in NuttX on ttyACM0
|
2015-07-13 20:52:48 -03:00
|
|
|
|
|
|
|
// FIONWRITE is also used for auto flow control detection
|
|
|
|
// Assume output flow control is not working if:
|
|
|
|
// port is configured for auto flow control
|
|
|
|
// and this is not the first write since flow control turned on
|
|
|
|
// and no data has been removed from the buffer since flow control turned on
|
|
|
|
// and more than .5 seconds elapsed after writing a total of > 5 characters
|
|
|
|
//
|
2016-10-05 13:11:26 -03:00
|
|
|
|
2013-02-18 21:02:46 -04:00
|
|
|
int nwrite = 0;
|
2014-02-10 20:22:08 -04:00
|
|
|
|
2013-02-18 21:02:46 -04:00
|
|
|
if (ioctl(_fd, FIONWRITE, (unsigned long)&nwrite) == 0) {
|
2015-07-13 20:52:48 -03:00
|
|
|
if (_flow_control == FLOW_CONTROL_AUTO) {
|
|
|
|
if (_first_write_time == 0) {
|
|
|
|
if (_total_written == 0) {
|
|
|
|
// save the remaining buffer bytes for comparison next write
|
|
|
|
_os_start_auto_space = nwrite;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
if (_os_start_auto_space - nwrite + 1 >= _total_written &&
|
2015-11-19 23:11:07 -04:00
|
|
|
(AP_HAL::micros64() - _first_write_time) > 500*1000UL) {
|
2015-07-13 20:52:48 -03:00
|
|
|
// it doesn't look like hw flow control is working
|
2016-10-05 13:11:26 -03:00
|
|
|
::printf("disabling flow control on %s _total_written=%u\n",
|
2015-07-13 20:52:48 -03:00
|
|
|
_devpath, (unsigned)_total_written);
|
|
|
|
set_flow_control(FLOW_CONTROL_DISABLE);
|
|
|
|
}
|
|
|
|
}
|
2014-02-10 20:22:08 -04:00
|
|
|
}
|
2013-02-18 21:02:46 -04:00
|
|
|
if (nwrite > n) {
|
|
|
|
nwrite = n;
|
|
|
|
}
|
|
|
|
if (nwrite > 0) {
|
|
|
|
ret = ::write(_fd, buf, nwrite);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (ret > 0) {
|
2015-11-19 23:11:07 -04:00
|
|
|
_last_write_time = AP_HAL::micros64();
|
2014-02-10 20:22:08 -04:00
|
|
|
_total_written += ret;
|
2015-07-13 20:52:48 -03:00
|
|
|
if (! _first_write_time && _total_written > 5) {
|
|
|
|
_first_write_time = _last_write_time;
|
|
|
|
}
|
2013-02-18 21:02:46 -04:00
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2015-11-19 23:11:07 -04:00
|
|
|
if (AP_HAL::micros64() - _last_write_time > 2000 &&
|
2014-02-10 20:22:08 -04:00
|
|
|
_flow_control == FLOW_CONTROL_DISABLE) {
|
2015-11-19 23:11:07 -04:00
|
|
|
_last_write_time = AP_HAL::micros64();
|
2016-10-05 13:11:26 -03:00
|
|
|
|
|
|
|
// we haven't done a successful write for 2ms, which means the
|
2013-02-18 21:02:46 -04:00
|
|
|
// port is running at less than 500 bytes/sec. Start
|
|
|
|
// discarding bytes, even if this is a blocking port. This
|
|
|
|
// prevents the ttyACM0 port blocking startup if the endpoint
|
|
|
|
// is not connected
|
|
|
|
return n;
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2013-03-20 01:41:52 -03:00
|
|
|
/*
|
|
|
|
try reading n bytes, handling an unresponsive port
|
|
|
|
*/
|
|
|
|
int PX4UARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
|
|
|
{
|
|
|
|
int ret = 0;
|
|
|
|
|
|
|
|
// the FIONREAD check is to cope with broken O_NONBLOCK behaviour
|
|
|
|
// in NuttX on ttyACM0
|
|
|
|
int nread = 0;
|
|
|
|
if (ioctl(_fd, FIONREAD, (unsigned long)&nread) == 0) {
|
|
|
|
if (nread > n) {
|
|
|
|
nread = n;
|
|
|
|
}
|
|
|
|
if (nread > 0) {
|
|
|
|
ret = ::read(_fd, buf, nread);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (ret > 0) {
|
2014-02-10 20:22:08 -04:00
|
|
|
_total_read += ret;
|
2013-03-20 01:41:52 -03:00
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2013-01-22 05:11:12 -04:00
|
|
|
/*
|
|
|
|
push any pending bytes to/from the serial port. This is called at
|
|
|
|
1kHz in the timer thread. Doing it this way reduces the system call
|
2016-10-05 13:11:26 -03:00
|
|
|
overhead in the main task enormously.
|
2013-01-22 05:11:12 -04:00
|
|
|
*/
|
|
|
|
void PX4UARTDriver::_timer_tick(void)
|
2013-01-04 17:09:23 -04:00
|
|
|
{
|
2016-07-30 08:54:37 -03:00
|
|
|
int ret;
|
|
|
|
uint32_t n;
|
2013-01-22 05:11:12 -04:00
|
|
|
|
|
|
|
if (!_initialised) return;
|
|
|
|
|
2013-11-04 23:41:42 -04:00
|
|
|
// don't try IO on a disconnected USB port
|
2018-05-15 21:42:49 -03:00
|
|
|
if (_is_usb && !hal.gpio->usb_connected()) {
|
2013-11-04 23:41:42 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2013-01-22 05:11:12 -04:00
|
|
|
_in_timer = true;
|
|
|
|
|
|
|
|
// write any pending bytes
|
2016-07-30 08:54:37 -03:00
|
|
|
n = _writebuf.available();
|
2013-01-22 05:11:12 -04:00
|
|
|
if (n > 0) {
|
2016-07-30 08:54:37 -03:00
|
|
|
ByteBuffer::IoVec vec[2];
|
2013-01-24 00:01:48 -04:00
|
|
|
perf_begin(_perf_uart);
|
2016-07-30 08:54:37 -03:00
|
|
|
const auto n_vec = _writebuf.peekiovec(vec, n);
|
|
|
|
for (int i = 0; i < n_vec; i++) {
|
|
|
|
ret = _write_fd(vec[i].data, (uint16_t)vec[i].len);
|
2016-10-05 13:17:14 -03:00
|
|
|
if (ret < 0) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
_writebuf.advance(ret);
|
|
|
|
|
|
|
|
/* We wrote less than we asked for, stop */
|
|
|
|
if ((unsigned)ret != vec[i].len) {
|
|
|
|
break;
|
|
|
|
}
|
2013-01-22 05:11:12 -04:00
|
|
|
}
|
2013-01-24 00:01:48 -04:00
|
|
|
perf_end(_perf_uart);
|
2013-01-22 05:11:12 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// try to fill the read buffer
|
2016-07-30 08:54:37 -03:00
|
|
|
ByteBuffer::IoVec vec[2];
|
|
|
|
|
|
|
|
perf_begin(_perf_uart);
|
|
|
|
const auto n_vec = _readbuf.reserve(vec, _readbuf.space());
|
|
|
|
for (int i = 0; i < n_vec; i++) {
|
|
|
|
ret = _read_fd(vec[i].data, vec[i].len);
|
2016-10-05 13:17:14 -03:00
|
|
|
if (ret < 0) {
|
2016-07-30 08:54:37 -03:00
|
|
|
break;
|
2016-10-05 13:17:14 -03:00
|
|
|
}
|
2016-07-30 08:54:37 -03:00
|
|
|
_readbuf.commit((unsigned)ret);
|
2016-10-05 13:17:14 -03:00
|
|
|
|
2018-05-15 21:42:49 -03:00
|
|
|
// update receive timestamp
|
|
|
|
_receive_timestamp[_receive_timestamp_idx^1] = AP_HAL::micros64();
|
|
|
|
_receive_timestamp_idx ^= 1;
|
|
|
|
|
2016-10-05 13:17:14 -03:00
|
|
|
/* stop reading as we read less than we asked for */
|
|
|
|
if ((unsigned)ret < vec[i].len) {
|
2016-07-30 08:54:37 -03:00
|
|
|
break;
|
2016-10-05 13:17:14 -03:00
|
|
|
}
|
2016-07-30 08:54:37 -03:00
|
|
|
}
|
|
|
|
perf_end(_perf_uart);
|
2013-01-22 05:11:12 -04:00
|
|
|
|
|
|
|
_in_timer = false;
|
2013-01-04 17:09:23 -04:00
|
|
|
}
|
|
|
|
|
2018-05-15 21:42:49 -03:00
|
|
|
/*
|
|
|
|
return timestamp estimate in microseconds for when the start of
|
|
|
|
a nbytes packet arrived on the uart. This should be treated as a
|
|
|
|
time constraint, not an exact time. It is guaranteed that the
|
|
|
|
packet did not start being received after this time, but it
|
|
|
|
could have been in a system buffer before the returned time.
|
|
|
|
|
|
|
|
This takes account of the baudrate of the link. For transports
|
|
|
|
that have no baudrate (such as USB) the time estimate may be
|
|
|
|
less accurate.
|
|
|
|
|
|
|
|
A return value of zero means the HAL does not support this API
|
|
|
|
*/
|
2018-05-16 18:01:14 -03:00
|
|
|
uint64_t PX4UARTDriver::receive_time_constraint_us(uint16_t nbytes)
|
2018-05-15 21:42:49 -03:00
|
|
|
{
|
|
|
|
uint64_t last_receive_us = _receive_timestamp[_receive_timestamp_idx];
|
|
|
|
if (_baudrate > 0 && !_is_usb) {
|
|
|
|
// assume 10 bits per byte. For USB we assume zero transport delay
|
2018-05-16 18:01:14 -03:00
|
|
|
uint32_t transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes+available());
|
2018-05-15 21:42:49 -03:00
|
|
|
last_receive_us -= transport_time_us;
|
|
|
|
}
|
|
|
|
return last_receive_us;
|
|
|
|
}
|
|
|
|
|
2016-10-05 13:11:26 -03:00
|
|
|
#endif
|