mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_Linux: default to hal.console on stdout
This commit is contained in:
parent
bcc9cdbf43
commit
bbac3265b2
@ -12,9 +12,9 @@
|
|||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
// 3 serial ports on Linux for now
|
// 3 serial ports on Linux for now
|
||||||
static LinuxUARTDriver uartADriver;
|
static LinuxUARTDriver uartADriver(true);
|
||||||
static LinuxUARTDriver uartBDriver;
|
static LinuxUARTDriver uartBDriver(false);
|
||||||
static LinuxUARTDriver uartCDriver;
|
static LinuxUARTDriver uartCDriver(false);
|
||||||
|
|
||||||
static LinuxSemaphore i2cSemaphore;
|
static LinuxSemaphore i2cSemaphore;
|
||||||
static LinuxI2CDriver i2cDriver(&i2cSemaphore, "/dev/i2c-1");
|
static LinuxI2CDriver i2cDriver(&i2cSemaphore, "/dev/i2c-1");
|
||||||
|
@ -20,10 +20,16 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
LinuxUARTDriver::LinuxUARTDriver() :
|
LinuxUARTDriver::LinuxUARTDriver(bool default_console) :
|
||||||
device_path(NULL),
|
device_path(NULL),
|
||||||
_fd(-1)
|
_rd_fd(-1),
|
||||||
|
_wr_fd(-1)
|
||||||
{
|
{
|
||||||
|
if (default_console) {
|
||||||
|
_rd_fd = 0;
|
||||||
|
_wr_fd = 1;
|
||||||
|
_console = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -44,14 +50,19 @@ void LinuxUARTDriver::begin(uint32_t b)
|
|||||||
|
|
||||||
void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||||
{
|
{
|
||||||
if (!_initialised) {
|
if (device_path == NULL && _console) {
|
||||||
|
_rd_fd = 0;
|
||||||
|
_wr_fd = 1;
|
||||||
|
rxS = 512;
|
||||||
|
txS = 512;
|
||||||
|
} else if (!_initialised) {
|
||||||
if (device_path == NULL) {
|
if (device_path == NULL) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint8_t retries = 0;
|
uint8_t retries = 0;
|
||||||
while (retries < 5) {
|
while (retries < 5) {
|
||||||
_fd = open(device_path, O_RDWR);
|
_rd_fd = open(device_path, O_RDWR);
|
||||||
if (_fd != -1) {
|
if (_rd_fd != -1) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// sleep a bit and retry. There seems to be a NuttX bug
|
// sleep a bit and retry. There seems to be a NuttX bug
|
||||||
@ -60,7 +71,8 @@ void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
hal.scheduler->delay(100);
|
hal.scheduler->delay(100);
|
||||||
retries++;
|
retries++;
|
||||||
}
|
}
|
||||||
if (_fd == -1) {
|
_wr_fd = _rd_fd;
|
||||||
|
if (_rd_fd == -1) {
|
||||||
fprintf(stdout, "Failed to open UART device %s - %s\n",
|
fprintf(stdout, "Failed to open UART device %s - %s\n",
|
||||||
device_path, strerror(errno));
|
device_path, strerror(errno));
|
||||||
return;
|
return;
|
||||||
@ -73,7 +85,7 @@ void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
|
|
||||||
// always run the file descriptor non-blocking, and deal with
|
// always run the file descriptor non-blocking, and deal with
|
||||||
// blocking IO in the higher level calls
|
// blocking IO in the higher level calls
|
||||||
fcntl(_fd, F_SETFL, fcntl(_fd, F_GETFL, 0) | O_NONBLOCK);
|
fcntl(_rd_fd, F_SETFL, fcntl(_rd_fd, F_GETFL, 0) | O_NONBLOCK);
|
||||||
|
|
||||||
if (rxS == 0) {
|
if (rxS == 0) {
|
||||||
rxS = 128;
|
rxS = 128;
|
||||||
@ -90,14 +102,14 @@ void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
_initialised = false;
|
_initialised = false;
|
||||||
while (_in_timer) hal.scheduler->delay(1);
|
while (_in_timer) hal.scheduler->delay(1);
|
||||||
|
|
||||||
if (b != 0) {
|
if (b != 0 && _rd_fd == _wr_fd) {
|
||||||
// set the baud rate
|
// set the baud rate
|
||||||
struct termios t;
|
struct termios t;
|
||||||
tcgetattr(_fd, &t);
|
tcgetattr(_rd_fd, &t);
|
||||||
cfsetspeed(&t, b);
|
cfsetspeed(&t, b);
|
||||||
// disable LF -> CR/LF
|
// disable LF -> CR/LF
|
||||||
t.c_oflag &= ~ONLCR;
|
t.c_oflag &= ~ONLCR;
|
||||||
tcsetattr(_fd, TCSANOW, &t);
|
tcsetattr(_rd_fd, TCSANOW, &t);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -138,10 +150,11 @@ void LinuxUARTDriver::end()
|
|||||||
{
|
{
|
||||||
_initialised = false;
|
_initialised = false;
|
||||||
while (_in_timer) hal.scheduler->delay(1);
|
while (_in_timer) hal.scheduler->delay(1);
|
||||||
if (_fd != -1) {
|
if (_rd_fd == _wr_fd && _rd_fd != -1) {
|
||||||
close(_fd);
|
close(_rd_fd);
|
||||||
_fd = -1;
|
|
||||||
}
|
}
|
||||||
|
_rd_fd = -1;
|
||||||
|
_wr_fd = -1;
|
||||||
if (_readbuf) {
|
if (_readbuf) {
|
||||||
free(_readbuf);
|
free(_readbuf);
|
||||||
_readbuf = NULL;
|
_readbuf = NULL;
|
||||||
@ -325,12 +338,12 @@ int LinuxUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
|||||||
int ret = 0;
|
int ret = 0;
|
||||||
|
|
||||||
struct pollfd fds;
|
struct pollfd fds;
|
||||||
fds.fd = _fd;
|
fds.fd = _wr_fd;
|
||||||
fds.events = POLLOUT;
|
fds.events = POLLOUT;
|
||||||
fds.revents = 0;
|
fds.revents = 0;
|
||||||
|
|
||||||
if (poll(&fds, 1, 0) == 1) {
|
if (poll(&fds, 1, 0) == 1) {
|
||||||
ret = ::write(_fd, buf, n);
|
ret = ::write(_wr_fd, buf, n);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (ret > 0) {
|
if (ret > 0) {
|
||||||
@ -347,7 +360,7 @@ int LinuxUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
|
|||||||
int LinuxUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
int LinuxUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
||||||
{
|
{
|
||||||
int ret;
|
int ret;
|
||||||
ret = ::read(_fd, buf, n);
|
ret = ::read(_rd_fd, buf, n);
|
||||||
if (ret > 0) {
|
if (ret > 0) {
|
||||||
BUF_ADVANCETAIL(_readbuf, ret);
|
BUF_ADVANCETAIL(_readbuf, ret);
|
||||||
}
|
}
|
||||||
|
@ -6,7 +6,7 @@
|
|||||||
|
|
||||||
class Linux::LinuxUARTDriver : public AP_HAL::UARTDriver {
|
class Linux::LinuxUARTDriver : public AP_HAL::UARTDriver {
|
||||||
public:
|
public:
|
||||||
LinuxUARTDriver();
|
LinuxUARTDriver(bool default_console);
|
||||||
/* Linux implementations of UARTDriver virtual methods */
|
/* Linux implementations of UARTDriver virtual methods */
|
||||||
void begin(uint32_t b);
|
void begin(uint32_t b);
|
||||||
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
||||||
@ -31,8 +31,10 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
const char *device_path;
|
const char *device_path;
|
||||||
int _fd;
|
int _rd_fd;
|
||||||
|
int _wr_fd;
|
||||||
bool _nonblocking_writes;
|
bool _nonblocking_writes;
|
||||||
|
bool _console;
|
||||||
volatile bool _initialised;
|
volatile bool _initialised;
|
||||||
volatile bool _in_timer;
|
volatile bool _in_timer;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user