Skip to content

Commit

Permalink
AP_HAL_Linux: support UNIX FIFO(named pipe) interface
Browse files Browse the repository at this point in the history
  • Loading branch information
rsaxvc committed Jul 24, 2023
1 parent 85eeffc commit 3305be7
Show file tree
Hide file tree
Showing 5 changed files with 170 additions and 6 deletions.
110 changes: 110 additions & 0 deletions libraries/AP_HAL_Linux/FIFODevice.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
#include "FIFODevice.h"

#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdio.h>
#include <unistd.h>

#include <AP_HAL/AP_HAL.h>

FIFODevice::FIFODevice(const char *rd_device, const char *wr_device):
_rd_device(rd_device), _wr_device(wr_device),
_rd_fd(-1), _wr_fd(-1)
{
}

FIFODevice::~FIFODevice()
{
}

bool FIFODevice::close()
{
bool ret = true;

if (_rd_fd >= 0) {
if (::close(_rd_fd) < 0) {
ret = false;
}
_rd_fd = -1;
}

if (_wr_fd >= 0) {
if (::close(_wr_fd) < 0) {
ret = false;
}
_wr_fd = -1;
}

return ret;
}

bool FIFODevice::open()
{
_rd_fd = ::open(_rd_device, O_CLOEXEC | O_NOCTTY | O_NONBLOCK | O_RDONLY);

if (_rd_fd < 0) {
::fprintf(stderr, "Failed to open FIFO device %s for reading - %s\n",
_rd_device, strerror(errno));
return false;
}

//O_RDWR is used only to allow opening a FIFO that has not been opened yet.
_wr_fd = ::open(_wr_device, O_CLOEXEC | O_NOCTTY | O_NONBLOCK | O_RDWR);

if (_wr_fd < 0) {
::fprintf(stderr, "Failed to open FIFO device %s for writing - %s\n",
_wr_device, strerror(errno));
::close(_rd_fd);
_rd_fd = -1;
return false;
}

return true;
}

ssize_t FIFODevice::read(uint8_t *buf, uint16_t n)
{
return ::read(_rd_fd, buf, n);
}

ssize_t FIFODevice::write(const uint8_t *buf, uint16_t n)
{
return ::write(_wr_fd, buf, n);
}

static void fifo_set_fd_blocking_helper(int fd, const char * devname, bool blocking)
{
int flags = fcntl(fd, F_GETFL, 0);

if (blocking) {
flags = flags & ~O_NONBLOCK;
} else {
flags = flags | O_NONBLOCK;
}

if (fcntl(fd, F_SETFL, flags) < 0) {
::fprintf(stderr, "Failed to set FIFO %s nonblocking: %s\n", devname, strerror(errno));
}
}

void FIFODevice::set_blocking(bool blocking)
{
fifo_set_fd_blocking_helper(_rd_fd, _rd_device, blocking);
fifo_set_fd_blocking_helper(_wr_fd, _wr_device, blocking);
}

void FIFODevice::set_speed(uint32_t baudrate)
{
//Ignored for FIFO: quite fast.
}

void FIFODevice::set_flow_control(AP_HAL::UARTDriver::flow_control flow_control_setting)
{
//Ignored for FIFO: effectively FLOW_CONTROL_ENABLE once pipe is opened
}

void FIFODevice::set_parity(int v)
{
//Ignored for FIFO: in-memory ring buffer
}
29 changes: 29 additions & 0 deletions libraries/AP_HAL_Linux/FIFODevice.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
#pragma once

#include "SerialDevice.h"

class FIFODevice: public SerialDevice
{
public:
FIFODevice(const char *rd_device, const char *wr_device);
virtual ~FIFODevice();

virtual bool open() override;
virtual bool close() override;
virtual ssize_t write(const uint8_t *buf, uint16_t n) override;
virtual ssize_t read(uint8_t *buf, uint16_t n) override;
virtual void set_blocking(bool blocking) override;
virtual void set_speed(uint32_t speed) override;
virtual void set_flow_control(enum AP_HAL::UARTDriver::flow_control flow_control_setting) override;
virtual AP_HAL::UARTDriver::flow_control get_flow_control(void) override
{
return AP_HAL::UARTDriver::flow_control::FLOW_CONTROL_DISABLE;
}
virtual void set_parity(int v) override;

private:
int _rd_fd = -1;
int _wr_fd = -1;
const char *_rd_device;
const char *_wr_device;
};
7 changes: 7 additions & 0 deletions libraries/AP_HAL_Linux/HAL_Linux_Class.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -299,6 +299,8 @@ void _usage(void)
printf("\tnetworking UDP:\n");
printf("\t --serial0 udp:11.0.0.255:14550:bcast\n");
printf("\t --serial0 udpin:0.0.0.0:14550\n");
printf("\tUnix Named Pipe / FIFO:\n");
printf("\t --serial0 fifo:/dev/socket/read_fifo:/dev/socket/write_fifo\n");
printf("\tcustom log path:\n");
printf("\t --log-directory /var/APM/logs\n");
printf("\t -l /var/APM/logs\n");
Expand Down Expand Up @@ -478,6 +480,11 @@ void HAL_Linux::setup_signal_handlers() const
sa.sa_handler = HAL_Linux::exit_signal_handler;
sigaction(SIGTERM, &sa, NULL);
sigaction(SIGINT, &sa, NULL);

struct sigaction sa_pipe = {};
sigemptyset(&sa_pipe.sa_mask);
sa_pipe.sa_handler = SIG_IGN; /* No-op SIGPIPE handler - handled by individual drivers */
sigaction(SIGPIPE, &sa_pipe, nullptr);
}

HAL_Linux hal_linux;
Expand Down
28 changes: 23 additions & 5 deletions libraries/AP_HAL_Linux/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include "ConsoleDevice.h"
#include "TCPServerDevice.h"
#include "FIFODevice.h"
#include "UARTDevice.h"
#include "UDPDevice.h"

Expand Down Expand Up @@ -125,6 +126,7 @@ void UARTDriver::_deallocate_buffers()
/*
Device path accepts the following syntaxes:
- /dev/ttyO1
- fifo:/dev/socket/rx:/dev/socket/tx
- tcp:*:1243:wait
- udp:192.168.2.15:1243
*/
Expand All @@ -136,7 +138,8 @@ AP_HAL::OwnPtr<SerialDevice> UARTDriver::_parseDevicePath(const char *arg)
return AP_HAL::OwnPtr<SerialDevice>(new UARTDevice(arg));
} else if (strncmp(arg, "tcp:", 4) != 0 &&
strncmp(arg, "udp:", 4) != 0 &&
strncmp(arg, "udpin:", 6)) {
strncmp(arg, "udpin:", 6) != 0 &&
strncmp(arg, "fifo:", 5) != 0) {
return nullptr;
}

Expand Down Expand Up @@ -169,8 +172,9 @@ AP_HAL::OwnPtr<SerialDevice> UARTDriver::_parseDevicePath(const char *arg)
_flag = nullptr;
}

_base_port = (uint16_t) atoi(port);
uint16_t base_port = (uint16_t) atoi(port);
_ip = strdup(ip);
_port = strdup(port);

/* Optional flag for TCP */
if (flag != nullptr) {
Expand All @@ -185,17 +189,31 @@ AP_HAL::OwnPtr<SerialDevice> UARTDriver::_parseDevicePath(const char *arg)
_packetise = true;
#endif
if (strcmp(protocol, "udp") == 0) {
device = new UDPDevice(_ip, _base_port, bcast, false);
device = new UDPDevice(_ip, base_port, bcast, false);
} else {
if (bcast) {
AP_HAL::panic("Can't combine udpin with bcast");
}
device = new UDPDevice(_ip, _base_port, false, true);
device = new UDPDevice(_ip, base_port, false, true);

}
} else if(strcmp(protocol,"fifo") == 0) {
const char * rx_fifo = _ip;
const char * tx_fifo = _port;
if(stat(_ip, &st) != 0) {
AP_HAL::panic("stat() RX fifo %s failed", rx_fifo);
} else if( !S_ISFIFO(st.st_mode)) {
AP_HAL::panic("RX file %s is not a FIFO", rx_fifo);
} else if(stat(_port, &st) != 0) {
AP_HAL::panic("stat() TX fifo %s failed", tx_fifo);
} else if( !S_ISFIFO(st.st_mode)) {
AP_HAL::panic("TX file %s is not a FIFO", tx_fifo);
} else {
return AP_HAL::OwnPtr<SerialDevice>(new FIFODevice(rx_fifo, tx_fifo));
}
} else {
bool wait = (_flag && strcmp(_flag, "wait") == 0);
device = new TCPServerDevice(_ip, _base_port, wait);
device = new TCPServerDevice(_ip, base_port, wait);
}

free(devstr);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_Linux/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,9 @@ class UARTDriver : public AP_HAL::UARTDriver {
AP_HAL::OwnPtr<SerialDevice> _device;
bool _console;
volatile bool _in_timer;
uint16_t _base_port;
uint32_t _baudrate;
char *_ip;
char *_port;
char *_flag;
bool _connected; // true if a client has connected
bool _packetise; // true if writes should try to be on mavlink boundaries
Expand Down

0 comments on commit 3305be7

Please sign in to comment.