forked from Archive/PX4-Autopilot
Compare commits
4 Commits
main
...
new_uart_d
Author | SHA1 | Date |
---|---|---|
Eric Katzfey | fbfb93ab26 | |
Eric Katzfey | 4b53be9444 | |
Eric Katzfey | 4217b43728 | |
Eric Katzfey | baa857d56f |
|
@ -3,6 +3,7 @@ CONFIG_BOARD_LINUX_TARGET=y
|
||||||
CONFIG_BOARD_TOOLCHAIN="aarch64-linux-gnu"
|
CONFIG_BOARD_TOOLCHAIN="aarch64-linux-gnu"
|
||||||
CONFIG_BOARD_ROOTFSDIR="/data/px4"
|
CONFIG_BOARD_ROOTFSDIR="/data/px4"
|
||||||
CONFIG_DRIVERS_ACTUATORS_MODAL_IO=y
|
CONFIG_DRIVERS_ACTUATORS_MODAL_IO=y
|
||||||
|
CONFIG_DRIVERS_GPS=y
|
||||||
CONFIG_DRIVERS_OSD_MSP_OSD=y
|
CONFIG_DRIVERS_OSD_MSP_OSD=y
|
||||||
CONFIG_DRIVERS_QSHELL_POSIX=y
|
CONFIG_DRIVERS_QSHELL_POSIX=y
|
||||||
CONFIG_MODULES_COMMANDER=y
|
CONFIG_MODULES_COMMANDER=y
|
||||||
|
|
|
@ -56,4 +56,5 @@ px4_add_module(
|
||||||
module.yaml
|
module.yaml
|
||||||
DEPENDS
|
DEPENDS
|
||||||
git_gps_devices
|
git_gps_devices
|
||||||
|
drivers__device
|
||||||
)
|
)
|
||||||
|
|
|
@ -45,11 +45,11 @@
|
||||||
#include <poll.h>
|
#include <poll.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include <termios.h>
|
|
||||||
#include <cstring>
|
#include <cstring>
|
||||||
|
|
||||||
#include <drivers/drv_sensor.h>
|
#include <drivers/drv_sensor.h>
|
||||||
#include <lib/drivers/device/Device.hpp>
|
#include <lib/drivers/device/Device.hpp>
|
||||||
|
#include <lib/drivers/device/Serial.hpp>
|
||||||
#include <lib/parameters/param.h>
|
#include <lib/parameters/param.h>
|
||||||
#include <mathlib/mathlib.h>
|
#include <mathlib/mathlib.h>
|
||||||
#include <matrix/math.hpp>
|
#include <matrix/math.hpp>
|
||||||
|
@ -81,6 +81,7 @@
|
||||||
#include <linux/spi/spidev.h>
|
#include <linux/spi/spidev.h>
|
||||||
#endif /* __PX4_LINUX */
|
#endif /* __PX4_LINUX */
|
||||||
|
|
||||||
|
using namespace device;
|
||||||
using namespace time_literals;
|
using namespace time_literals;
|
||||||
|
|
||||||
#define TIMEOUT_1HZ 1300 //!< Timeout time in mS, 1000 mS (1Hz) + 300 mS delta for error
|
#define TIMEOUT_1HZ 1300 //!< Timeout time in mS, 1000 mS (1Hz) + 300 mS delta for error
|
||||||
|
@ -169,7 +170,10 @@ public:
|
||||||
void reset_if_scheduled();
|
void reset_if_scheduled();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
int _serial_fd{-1}; ///< serial interface to GPS
|
#ifdef __PX4_LINUX
|
||||||
|
int _spi_fd {-1}; ///< SPI interface to GPS
|
||||||
|
#endif
|
||||||
|
Serial *_uart = nullptr;
|
||||||
unsigned _baudrate{0}; ///< current baudrate
|
unsigned _baudrate{0}; ///< current baudrate
|
||||||
const unsigned _configured_baudrate{0}; ///< configured baudrate (0=auto-detect)
|
const unsigned _configured_baudrate{0}; ///< configured baudrate (0=auto-detect)
|
||||||
char _port[20] {}; ///< device / serial port path
|
char _port[20] {}; ///< device / serial port path
|
||||||
|
@ -329,8 +333,10 @@ GPS::GPS(const char *path, gps_driver_mode_t mode, GPSHelper::Interface interfac
|
||||||
char c = _port[strlen(_port) - 1]; // last digit of path (eg /dev/ttyS2)
|
char c = _port[strlen(_port) - 1]; // last digit of path (eg /dev/ttyS2)
|
||||||
set_device_bus(c - 48); // sub 48 to convert char to integer
|
set_device_bus(c - 48); // sub 48 to convert char to integer
|
||||||
|
|
||||||
|
#ifdef __PX4_LINUX
|
||||||
} else if (_interface == GPSHelper::Interface::SPI) {
|
} else if (_interface == GPSHelper::Interface::SPI) {
|
||||||
set_device_bus_type(device::Device::DeviceBusType::DeviceBusType_SPI);
|
set_device_bus_type(device::Device::DeviceBusType::DeviceBusType_SPI);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_mode == gps_driver_mode_t::None) {
|
if (_mode == gps_driver_mode_t::None) {
|
||||||
|
@ -403,10 +409,22 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user)
|
||||||
return num_read;
|
return num_read;
|
||||||
}
|
}
|
||||||
|
|
||||||
case GPSCallbackType::writeDeviceData:
|
case GPSCallbackType::writeDeviceData: {
|
||||||
gps->dumpGpsData((uint8_t *)data1, (size_t)data2, gps_dump_comm_mode_t::Full, true);
|
gps->dumpGpsData((uint8_t *)data1, (size_t)data2, gps_dump_comm_mode_t::Full, true);
|
||||||
|
|
||||||
return ::write(gps->_serial_fd, data1, (size_t)data2);
|
int ret = 0;
|
||||||
|
|
||||||
|
if (gps->_uart) {
|
||||||
|
ret = gps->_uart->write((void *) data1, (size_t) data2);
|
||||||
|
|
||||||
|
#ifdef __PX4_LINUX
|
||||||
|
} else if (gps->_spi_fd >= 0) {
|
||||||
|
ret = ::write(gps->_spi_fd, data1, (size_t)data2);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
case GPSCallbackType::setBaudrate:
|
case GPSCallbackType::setBaudrate:
|
||||||
return gps->setBaudrate(data2);
|
return gps->setBaudrate(data2);
|
||||||
|
@ -437,10 +455,11 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user)
|
||||||
// as of 2021 setting the time on Nuttx temporarily pauses interrupts
|
// as of 2021 setting the time on Nuttx temporarily pauses interrupts
|
||||||
// so only set the time if it is very wrong.
|
// so only set the time if it is very wrong.
|
||||||
// TODO: clock slewing of the RTC for small time differences
|
// TODO: clock slewing of the RTC for small time differences
|
||||||
|
#ifndef __PX4_QURT
|
||||||
px4_clock_settime(CLOCK_REALTIME, &rtc_gps_time);
|
px4_clock_settime(CLOCK_REALTIME, &rtc_gps_time);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -449,72 +468,64 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user)
|
||||||
|
|
||||||
int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout)
|
int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout)
|
||||||
{
|
{
|
||||||
|
int ret = 0;
|
||||||
|
const unsigned character_count = 32; // minimum bytes that we want to read
|
||||||
|
const int max_timeout = 50;
|
||||||
|
int timeout_adjusted = math::min(max_timeout, timeout);
|
||||||
|
|
||||||
handleInjectDataTopic();
|
handleInjectDataTopic();
|
||||||
|
|
||||||
#if !defined(__PX4_QURT)
|
if ((_interface == GPSHelper::Interface::UART) && (_uart)) {
|
||||||
|
ret = _uart->readAtLeast(buf, buf_length, character_count, timeout_adjusted);
|
||||||
|
|
||||||
/* For non QURT, use the usual polling. */
|
// SPI is only supported on Linux
|
||||||
|
#if defined(__PX4_LINUX)
|
||||||
|
|
||||||
//Poll only for the serial data. In the same thread we also need to handle orb messages,
|
} else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd >= 0)) {
|
||||||
//so ideally we would poll on both, the serial fd and orb subscription. Unfortunately the
|
|
||||||
//two pollings use different underlying mechanisms (at least under posix), which makes this
|
|
||||||
//impossible. Instead we limit the maximum polling interval and regularly check for new orb
|
|
||||||
//messages.
|
|
||||||
//FIXME: add a unified poll() API
|
|
||||||
const int max_timeout = 50;
|
|
||||||
|
|
||||||
pollfd fds[1];
|
//Poll only for the SPI data. In the same thread we also need to handle orb messages,
|
||||||
fds[0].fd = _serial_fd;
|
//so ideally we would poll on both, the SPI fd and orb subscription. Unfortunately the
|
||||||
fds[0].events = POLLIN;
|
//two pollings use different underlying mechanisms (at least under posix), which makes this
|
||||||
|
//impossible. Instead we limit the maximum polling interval and regularly check for new orb
|
||||||
|
//messages.
|
||||||
|
//FIXME: add a unified poll() API
|
||||||
|
|
||||||
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), math::min(max_timeout, timeout));
|
pollfd fds[1];
|
||||||
|
fds[0].fd = _spi_fd;
|
||||||
|
fds[0].events = POLLIN;
|
||||||
|
|
||||||
if (ret > 0) {
|
ret = poll(fds, sizeof(fds) / sizeof(fds[0]), timeout_adjusted);
|
||||||
/* if we have new data from GPS, go handle it */
|
|
||||||
if (fds[0].revents & POLLIN) {
|
|
||||||
/*
|
|
||||||
* We are here because poll says there is some data, so this
|
|
||||||
* won't block even on a blocking device. But don't read immediately
|
|
||||||
* by 1-2 bytes, wait for some more data to save expensive read() calls.
|
|
||||||
* If we have all requested data available, read it without waiting.
|
|
||||||
* If more bytes are available, we'll go back to poll() again.
|
|
||||||
*/
|
|
||||||
const unsigned character_count = 32; // minimum bytes that we want to read
|
|
||||||
unsigned baudrate = _baudrate == 0 ? 115200 : _baudrate;
|
|
||||||
const unsigned sleeptime = character_count * 1000000 / (baudrate / 10);
|
|
||||||
|
|
||||||
#ifdef __PX4_NUTTX
|
if (ret > 0) {
|
||||||
int err = 0;
|
/* if we have new data from GPS, go handle it */
|
||||||
int bytes_available = 0;
|
if (fds[0].revents & POLLIN) {
|
||||||
err = ::ioctl(_serial_fd, FIONREAD, (unsigned long)&bytes_available);
|
/*
|
||||||
|
* We are here because poll says there is some data, so this
|
||||||
|
* won't block even on a blocking device. But don't read immediately
|
||||||
|
* by 1-2 bytes, wait for some more data to save expensive read() calls.
|
||||||
|
* If we have all requested data available, read it without waiting.
|
||||||
|
* If more bytes are available, we'll go back to poll() again.
|
||||||
|
*/
|
||||||
|
unsigned baudrate = _baudrate == 0 ? 115200 : _baudrate;
|
||||||
|
const unsigned sleeptime = character_count * 1000000 / (baudrate / 10);
|
||||||
|
|
||||||
if (err != 0 || bytes_available < (int)character_count) {
|
|
||||||
px4_usleep(sleeptime);
|
px4_usleep(sleeptime);
|
||||||
|
|
||||||
|
ret = ::read(_spi_fd, buf, buf_length);
|
||||||
|
|
||||||
|
if (ret > 0) {
|
||||||
|
_num_bytes_read += ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
} else {
|
||||||
|
ret = -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
|
||||||
px4_usleep(sleeptime);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
ret = ::read(_serial_fd, buf, buf_length);
|
|
||||||
|
|
||||||
if (ret > 0) {
|
|
||||||
_num_bytes_read += ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
ret = -1;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
|
|
||||||
#else
|
|
||||||
/* For QURT, just use read for now, since this doesn't block, we need to slow it down
|
|
||||||
* just a bit. */
|
|
||||||
px4_usleep(10000);
|
|
||||||
return ::read(_serial_fd, buf, buf_length);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void GPS::handleInjectDataTopic()
|
void GPS::handleInjectDataTopic()
|
||||||
|
@ -583,105 +594,38 @@ bool GPS::injectData(uint8_t *data, size_t len)
|
||||||
{
|
{
|
||||||
dumpGpsData(data, len, gps_dump_comm_mode_t::Full, true);
|
dumpGpsData(data, len, gps_dump_comm_mode_t::Full, true);
|
||||||
|
|
||||||
size_t written = ::write(_serial_fd, data, len);
|
size_t written = 0;
|
||||||
::fsync(_serial_fd);
|
|
||||||
|
if ((_interface == GPSHelper::Interface::UART) && (_uart)) {
|
||||||
|
written = _uart->write((const void *) data, len);
|
||||||
|
|
||||||
|
#ifdef __PX4_LINUX
|
||||||
|
|
||||||
|
} else if (_interface == GPSHelper::Interface::SPI) {
|
||||||
|
written = ::write(_spi_fd, data, len);
|
||||||
|
::fsync(_spi_fd);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
return written == len;
|
return written == len;
|
||||||
}
|
}
|
||||||
|
|
||||||
int GPS::setBaudrate(unsigned baud)
|
int GPS::setBaudrate(unsigned baud)
|
||||||
{
|
{
|
||||||
/* process baud rate */
|
if (_interface == GPSHelper::Interface::UART) {
|
||||||
int speed;
|
if ((_uart) && (_uart->setBaudrate(baud))) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
switch (baud) {
|
#ifdef __PX4_LINUX
|
||||||
case 9600: speed = B9600; break;
|
|
||||||
|
|
||||||
case 19200: speed = B19200; break;
|
} else if (_interface == GPSHelper::Interface::SPI) {
|
||||||
|
// Can't set the baudrate on a SPI port but just return a success
|
||||||
case 38400: speed = B38400; break;
|
return 0;
|
||||||
|
|
||||||
case 57600: speed = B57600; break;
|
|
||||||
|
|
||||||
case 115200: speed = B115200; break;
|
|
||||||
|
|
||||||
case 230400: speed = B230400; break;
|
|
||||||
|
|
||||||
#ifndef B460800
|
|
||||||
#define B460800 460800
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case 460800: speed = B460800; break;
|
|
||||||
|
|
||||||
#ifndef B921600
|
|
||||||
#define B921600 921600
|
|
||||||
#endif
|
|
||||||
|
|
||||||
case 921600: speed = B921600; break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
PX4_ERR("ERR: unknown baudrate: %d", baud);
|
|
||||||
return -EINVAL;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
struct termios uart_config;
|
return -1;
|
||||||
|
|
||||||
int termios_state;
|
|
||||||
|
|
||||||
/* fill the struct for the new configuration */
|
|
||||||
tcgetattr(_serial_fd, &uart_config);
|
|
||||||
|
|
||||||
/* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */
|
|
||||||
|
|
||||||
//
|
|
||||||
// Input flags - Turn off input processing
|
|
||||||
//
|
|
||||||
// convert break to null byte, no CR to NL translation,
|
|
||||||
// no NL to CR translation, don't mark parity errors or breaks
|
|
||||||
// no input parity check, don't strip high bit off,
|
|
||||||
// no XON/XOFF software flow control
|
|
||||||
//
|
|
||||||
uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
|
|
||||||
INLCR | PARMRK | INPCK | ISTRIP | IXON);
|
|
||||||
//
|
|
||||||
// Output flags - Turn off output processing
|
|
||||||
//
|
|
||||||
// no CR to NL translation, no NL to CR-NL translation,
|
|
||||||
// no NL to CR translation, no column 0 CR suppression,
|
|
||||||
// no Ctrl-D suppression, no fill characters, no case mapping,
|
|
||||||
// no local output processing
|
|
||||||
//
|
|
||||||
// config.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
|
|
||||||
// ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
|
|
||||||
uart_config.c_oflag = 0;
|
|
||||||
|
|
||||||
//
|
|
||||||
// No line processing
|
|
||||||
//
|
|
||||||
// echo off, echo newline off, canonical mode off,
|
|
||||||
// extended input processing off, signal chars off
|
|
||||||
//
|
|
||||||
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
|
|
||||||
|
|
||||||
/* no parity, one stop bit, disable flow control */
|
|
||||||
uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS);
|
|
||||||
|
|
||||||
/* set baud rate */
|
|
||||||
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
|
|
||||||
GPS_ERR("ERR: %d (cfsetispeed)", termios_state);
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
|
|
||||||
GPS_ERR("ERR: %d (cfsetospeed)", termios_state);
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) {
|
|
||||||
GPS_ERR("ERR: %d (tcsetattr)", termios_state);
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void GPS::initializeCommunicationDump()
|
void GPS::initializeCommunicationDump()
|
||||||
|
@ -840,31 +784,58 @@ GPS::run()
|
||||||
_helper = nullptr;
|
_helper = nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_serial_fd < 0) {
|
if ((_interface == GPSHelper::Interface::UART) && (_uart == nullptr)) {
|
||||||
/* open the serial port */
|
|
||||||
_serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
|
|
||||||
|
|
||||||
if (_serial_fd < 0) {
|
// Create the UART port instance
|
||||||
PX4_ERR("failed to open %s err: %d", _port, errno);
|
_uart = new Serial(_port);
|
||||||
px4_sleep(1);
|
|
||||||
|
if (_uart == nullptr) {
|
||||||
|
PX4_ERR("Error creating serial device %s", _port);
|
||||||
|
px4_usleep(100000);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((_interface == GPSHelper::Interface::UART) && (! _uart->isOpen())) {
|
||||||
|
// Configure the desired baudrate if one was specified by the user.
|
||||||
|
// Otherwise the default baudrate will be used.
|
||||||
|
if (_configured_baudrate) {
|
||||||
|
if (! _uart->setBaudrate(_configured_baudrate)) {
|
||||||
|
PX4_ERR("Error setting baudrate to %u on %s", _configured_baudrate, _port);
|
||||||
|
px4_usleep(100000);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Open the UART. If this is successful then the UART is ready to use.
|
||||||
|
if (! _uart->open()) {
|
||||||
|
PX4_ERR("Error opening serial device %s", _port);
|
||||||
|
px4_usleep(100000);
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef __PX4_LINUX
|
#ifdef __PX4_LINUX
|
||||||
|
|
||||||
if (_interface == GPSHelper::Interface::SPI) {
|
} else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd < 0)) {
|
||||||
int spi_speed = 1000000; // make sure the bus speed is not too high (required on RPi)
|
_spi_fd = ::open(_port, O_RDWR | O_NOCTTY);
|
||||||
int status_value = ::ioctl(_serial_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);
|
|
||||||
|
|
||||||
if (status_value < 0) {
|
if (_spi_fd < 0) {
|
||||||
PX4_ERR("SPI_IOC_WR_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
|
PX4_ERR("failed to open SPI port %s err: %d", _port, errno);
|
||||||
}
|
px4_sleep(1);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
status_value = ::ioctl(_serial_fd, SPI_IOC_RD_MAX_SPEED_HZ, &spi_speed);
|
int spi_speed = 1000000; // make sure the bus speed is not too high (required on RPi)
|
||||||
|
int status_value = ::ioctl(_spi_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);
|
||||||
|
|
||||||
if (status_value < 0) {
|
if (status_value < 0) {
|
||||||
PX4_ERR("SPI_IOC_RD_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
|
PX4_ERR("SPI_IOC_WR_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
status_value = ::ioctl(_spi_fd, SPI_IOC_RD_MAX_SPEED_HZ, &spi_speed);
|
||||||
|
|
||||||
|
if (status_value < 0) {
|
||||||
|
PX4_ERR("SPI_IOC_RD_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif /* __PX4_LINUX */
|
#endif /* __PX4_LINUX */
|
||||||
|
@ -1056,9 +1027,17 @@ GPS::run()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_serial_fd >= 0) {
|
if ((_interface == GPSHelper::Interface::UART) && (_uart)) {
|
||||||
::close(_serial_fd);
|
(void) _uart->close();
|
||||||
_serial_fd = -1;
|
delete _uart;
|
||||||
|
_uart = nullptr;
|
||||||
|
|
||||||
|
#ifdef __PX4_LINUX
|
||||||
|
|
||||||
|
} else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd >= 0)) {
|
||||||
|
::close(_spi_fd);
|
||||||
|
_spi_fd = -1;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_mode_auto) {
|
if (_mode_auto) {
|
||||||
|
@ -1477,12 +1456,12 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'i':
|
case 'i':
|
||||||
if (!strcmp(myoptarg, "spi")) {
|
if (!strcmp(myoptarg, "uart")) {
|
||||||
interface = GPSHelper::Interface::SPI;
|
|
||||||
|
|
||||||
} else if (!strcmp(myoptarg, "uart")) {
|
|
||||||
interface = GPSHelper::Interface::UART;
|
interface = GPSHelper::Interface::UART;
|
||||||
|
#ifdef __PX4_LINUX
|
||||||
|
} else if (!strcmp(myoptarg, "spi")) {
|
||||||
|
interface = GPSHelper::Interface::SPI;
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
PX4_ERR("unknown interface: %s", myoptarg);
|
PX4_ERR("unknown interface: %s", myoptarg);
|
||||||
error_flag = true;
|
error_flag = true;
|
||||||
|
@ -1490,12 +1469,12 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'j':
|
case 'j':
|
||||||
if (!strcmp(myoptarg, "spi")) {
|
if (!strcmp(myoptarg, "uart")) {
|
||||||
interface_secondary = GPSHelper::Interface::SPI;
|
|
||||||
|
|
||||||
} else if (!strcmp(myoptarg, "uart")) {
|
|
||||||
interface_secondary = GPSHelper::Interface::UART;
|
interface_secondary = GPSHelper::Interface::UART;
|
||||||
|
#ifdef __PX4_LINUX
|
||||||
|
} else if (!strcmp(myoptarg, "spi")) {
|
||||||
|
interface_secondary = GPSHelper::Interface::SPI;
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
PX4_ERR("unknown interface for secondary: %s", myoptarg);
|
PX4_ERR("unknown interface for secondary: %s", myoptarg);
|
||||||
error_flag = true;
|
error_flag = true;
|
||||||
|
|
|
@ -40,20 +40,31 @@ if (${PX4_PLATFORM} STREQUAL "nuttx")
|
||||||
if ("${CONFIG_SPI}" STREQUAL "y")
|
if ("${CONFIG_SPI}" STREQUAL "y")
|
||||||
list(APPEND SRCS_PLATFORM nuttx/SPI.cpp)
|
list(APPEND SRCS_PLATFORM nuttx/SPI.cpp)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
list(APPEND SRCS_PLATFORM nuttx/SerialImpl.cpp)
|
||||||
elseif((${PX4_PLATFORM} MATCHES "qurt"))
|
elseif((${PX4_PLATFORM} MATCHES "qurt"))
|
||||||
list(APPEND SRCS_PLATFORM qurt/I2C.cpp)
|
list(APPEND SRCS_PLATFORM qurt/I2C.cpp)
|
||||||
list(APPEND SRCS_PLATFORM qurt/SPI.cpp)
|
list(APPEND SRCS_PLATFORM qurt/SPI.cpp)
|
||||||
|
list(APPEND SRCS_PLATFORM qurt/SerialImpl.cpp)
|
||||||
list(APPEND SRCS_PLATFORM qurt/uart.c)
|
list(APPEND SRCS_PLATFORM qurt/uart.c)
|
||||||
elseif(UNIX AND NOT APPLE) #TODO: add linux PX4 platform type
|
elseif(UNIX AND NOT APPLE) #TODO: add linux PX4 platform type
|
||||||
# Linux I2Cdev and SPIdev
|
# Linux I2Cdev and SPIdev
|
||||||
list(APPEND SRCS_PLATFORM
|
if ("${CONFIG_I2C}" STREQUAL "y")
|
||||||
posix/I2C.cpp
|
list(APPEND SRCS_PLATFORM posix/I2C.cpp)
|
||||||
posix/SPI.cpp
|
endif()
|
||||||
)
|
|
||||||
|
if ("${CONFIG_SPI}" STREQUAL "y")
|
||||||
|
list(APPEND SRCS_PLATFORM posix/SPI.cpp)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
list(APPEND SRCS_PLATFORM posix/SerialImpl.cpp)
|
||||||
|
list(APPEND SRCS_PLATFORM posix/SerialSBUSImpl.cpp)
|
||||||
|
list(APPEND SRCS_PLATFORM posix/SerialStandardImpl.cpp)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
px4_add_library(drivers__device
|
px4_add_library(drivers__device
|
||||||
CDev.cpp
|
CDev.cpp
|
||||||
|
Serial.cpp
|
||||||
${SRCS_PLATFORM}
|
${SRCS_PLATFORM}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,103 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include "Serial.hpp"
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
Serial::Serial(const char *port, uint32_t baudrate) :
|
||||||
|
_impl(port, baudrate)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial::~Serial()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::open()
|
||||||
|
{
|
||||||
|
return _impl.open();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::isOpen() const
|
||||||
|
{
|
||||||
|
return _impl.isOpen();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::close()
|
||||||
|
{
|
||||||
|
return _impl.close();
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t Serial::read(uint8_t *buffer, size_t buffer_size)
|
||||||
|
{
|
||||||
|
return _impl.read(buffer, buffer_size);
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
|
||||||
|
{
|
||||||
|
return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_us);
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t Serial::write(const void *buffer, size_t buffer_size)
|
||||||
|
{
|
||||||
|
return _impl.write(buffer, buffer_size);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t Serial::getBaudrate() const
|
||||||
|
{
|
||||||
|
return _impl.getBaudrate();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setBaudrate(uint32_t baudrate)
|
||||||
|
{
|
||||||
|
return _impl.setBaudrate(baudrate);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getSBUSMode() const
|
||||||
|
{
|
||||||
|
return _impl.getSBUSMode();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setSBUSMode(bool enable)
|
||||||
|
{
|
||||||
|
return _impl.setSBUSMode(enable);
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *Serial::getPort() const
|
||||||
|
{
|
||||||
|
return _impl.getPort();
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,89 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
// Bring in the correct platform implementation
|
||||||
|
#ifdef __PX4_NUTTX
|
||||||
|
#include "nuttx/SerialImpl.hpp"
|
||||||
|
#elif defined(__PX4_QURT)
|
||||||
|
#include "qurt/SerialImpl.hpp"
|
||||||
|
#else
|
||||||
|
#include "posix/SerialImpl.hpp"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
namespace device __EXPORT
|
||||||
|
{
|
||||||
|
|
||||||
|
class Serial
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
// Baud rate can be selected with constructor or by using setBaudrate
|
||||||
|
Serial(const char *port, uint32_t baudrate = 0);
|
||||||
|
virtual ~Serial();
|
||||||
|
|
||||||
|
// Open sets up the port and gets it configured. Unless an alternate mode
|
||||||
|
// is selected the port will be configured with parity disabled and 1 stop bit.
|
||||||
|
bool open();
|
||||||
|
bool isOpen() const;
|
||||||
|
|
||||||
|
bool close();
|
||||||
|
|
||||||
|
ssize_t read(uint8_t *buffer, size_t buffer_size);
|
||||||
|
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
|
||||||
|
|
||||||
|
ssize_t write(const void *buffer, size_t buffer_size);
|
||||||
|
|
||||||
|
uint32_t getBaudrate() const;
|
||||||
|
|
||||||
|
// If the port has already been opened it will be reconfigured with a change
|
||||||
|
// of baudrate.
|
||||||
|
bool setBaudrate(uint32_t baudrate);
|
||||||
|
|
||||||
|
// SBUS has special configuration considerations and methods so it
|
||||||
|
// is given a special mode. It has parity enabled and 2 stop bits
|
||||||
|
bool getSBUSMode() const;
|
||||||
|
bool setSBUSMode(bool enable);
|
||||||
|
|
||||||
|
const char *getPort() const;
|
||||||
|
|
||||||
|
private:
|
||||||
|
// Disable copy constructors
|
||||||
|
Serial(const Serial &);
|
||||||
|
Serial &operator=(const Serial &);
|
||||||
|
|
||||||
|
// platform implementation
|
||||||
|
SerialImpl _impl;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,363 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include "SerialImpl.hpp"
|
||||||
|
#include <string.h> // strncpy
|
||||||
|
#include <termios.h>
|
||||||
|
#include <px4_log.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <poll.h>
|
||||||
|
#include <drivers/drv_hrt.h>
|
||||||
|
#include <board_config.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
SerialImpl::SerialImpl(const char *port, uint32_t baudrate)
|
||||||
|
{
|
||||||
|
if (port) {
|
||||||
|
strncpy(_port, port, sizeof(_port) - 1);
|
||||||
|
_port[sizeof(_port) - 1] = '\0';
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_port[0] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (baudrate) {
|
||||||
|
_baudrate = baudrate;
|
||||||
|
} else {
|
||||||
|
// If baudrate is zero then choose a reasonable default
|
||||||
|
_baudrate = 9600;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
SerialImpl::~SerialImpl()
|
||||||
|
{
|
||||||
|
if (isOpen()) {
|
||||||
|
close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::configure()
|
||||||
|
{
|
||||||
|
struct termios uart_config;
|
||||||
|
|
||||||
|
if (_SBUSMode) {
|
||||||
|
if (_baudrate != DEFAULT_SBUS_BAUDRATE) {
|
||||||
|
PX4_WARN("Warning, SBUS baud rate being set to %lu", _baudrate);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* even parity, two stop bits */
|
||||||
|
tcgetattr(_serial_fd, &uart_config);
|
||||||
|
cfsetspeed(&uart_config, _baudrate);
|
||||||
|
uart_config.c_cflag |= (CSTOPB | PARENB);
|
||||||
|
tcsetattr(_serial_fd, TCSANOW, &uart_config);
|
||||||
|
|
||||||
|
if (board_rc_singlewire(_port)) {
|
||||||
|
/* only defined in configs capable of IOCTL
|
||||||
|
* Note It is never turned off
|
||||||
|
*/
|
||||||
|
#ifdef TIOCSSINGLEWIRE
|
||||||
|
ioctl(_serial_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
/* process baud rate */
|
||||||
|
int speed;
|
||||||
|
|
||||||
|
switch (_baudrate) {
|
||||||
|
case 9600: speed = B9600; break;
|
||||||
|
|
||||||
|
case 19200: speed = B19200; break;
|
||||||
|
|
||||||
|
case 38400: speed = B38400; break;
|
||||||
|
|
||||||
|
case 57600: speed = B57600; break;
|
||||||
|
|
||||||
|
case 115200: speed = B115200; break;
|
||||||
|
|
||||||
|
case 230400: speed = B230400; break;
|
||||||
|
|
||||||
|
#ifndef B460800
|
||||||
|
#define B460800 460800
|
||||||
|
#endif
|
||||||
|
|
||||||
|
case 460800: speed = B460800; break;
|
||||||
|
|
||||||
|
#ifndef B921600
|
||||||
|
#define B921600 921600
|
||||||
|
#endif
|
||||||
|
|
||||||
|
case 921600: speed = B921600; break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
PX4_ERR("ERR: unknown baudrate: %lu", _baudrate);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
int termios_state;
|
||||||
|
|
||||||
|
/* fill the struct for the new configuration */
|
||||||
|
if ((termios_state = tcgetattr(_serial_fd, &uart_config)) < 0) {
|
||||||
|
PX4_ERR("ERR: %d (tcgetattr)", termios_state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */
|
||||||
|
|
||||||
|
//
|
||||||
|
// Input flags - Turn off input processing
|
||||||
|
//
|
||||||
|
// convert break to null byte, no CR to NL translation,
|
||||||
|
// no NL to CR translation, don't mark parity errors or breaks
|
||||||
|
// no input parity check, don't strip high bit off,
|
||||||
|
// no XON/XOFF software flow control
|
||||||
|
//
|
||||||
|
uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
|
||||||
|
INLCR | PARMRK | INPCK | ISTRIP | IXON);
|
||||||
|
|
||||||
|
//
|
||||||
|
// Output flags - Turn off output processing
|
||||||
|
//
|
||||||
|
// no CR to NL translation, no NL to CR-NL translation,
|
||||||
|
// no NL to CR translation, no column 0 CR suppression,
|
||||||
|
// no Ctrl-D suppression, no fill characters, no case mapping,
|
||||||
|
// no local output processing
|
||||||
|
//
|
||||||
|
// config.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
|
||||||
|
// ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
|
||||||
|
uart_config.c_oflag = 0;
|
||||||
|
|
||||||
|
//
|
||||||
|
// No line processing
|
||||||
|
//
|
||||||
|
// echo off, echo newline off, canonical mode off,
|
||||||
|
// extended input processing off, signal chars off
|
||||||
|
//
|
||||||
|
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
|
||||||
|
|
||||||
|
/* no parity, one stop bit, disable flow control */
|
||||||
|
uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS);
|
||||||
|
|
||||||
|
/* set baud rate */
|
||||||
|
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
|
||||||
|
PX4_ERR("ERR: %d (cfsetispeed)", termios_state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
|
||||||
|
PX4_ERR("ERR: %d (cfsetospeed)", termios_state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) {
|
||||||
|
PX4_ERR("ERR: %d (tcsetattr)", termios_state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::open()
|
||||||
|
{
|
||||||
|
if (isOpen()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Open the serial port
|
||||||
|
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
|
||||||
|
|
||||||
|
if (serial_fd < 0) {
|
||||||
|
PX4_ERR("failed to open %s err: %d", _port, errno);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
_serial_fd = serial_fd;
|
||||||
|
|
||||||
|
// Configure the serial port
|
||||||
|
if (! configure()) {
|
||||||
|
PX4_ERR("failed to configure %s err: %d", _port, errno);
|
||||||
|
close();
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
_open = true;
|
||||||
|
|
||||||
|
return _open;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::isOpen() const
|
||||||
|
{
|
||||||
|
return _open;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::close()
|
||||||
|
{
|
||||||
|
if (_serial_fd >= 0) {
|
||||||
|
::close(_serial_fd);
|
||||||
|
}
|
||||||
|
|
||||||
|
_serial_fd = -1;
|
||||||
|
_open = false;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot read from serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int ret = ::read(_serial_fd, buffer, buffer_size);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
PX4_DEBUG("%s read error %d", _port, ret);
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (buffer_size < character_count) {
|
||||||
|
PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
const hrt_abstime start_time_us = hrt_absolute_time();
|
||||||
|
int total_bytes_read = 0;
|
||||||
|
|
||||||
|
while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) {
|
||||||
|
// Poll for incoming UART data.
|
||||||
|
pollfd fds[1];
|
||||||
|
fds[0].fd = _serial_fd;
|
||||||
|
fds[0].events = POLLIN;
|
||||||
|
|
||||||
|
hrt_abstime remaining_time = timeout_us - hrt_elapsed_time(&start_time_us);
|
||||||
|
|
||||||
|
if (remaining_time <= 0) { break; }
|
||||||
|
|
||||||
|
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), remaining_time);
|
||||||
|
|
||||||
|
if (ret > 0) {
|
||||||
|
if (fds[0].revents & POLLIN) {
|
||||||
|
ret = read(&buffer[total_bytes_read], buffer_size - total_bytes_read);
|
||||||
|
|
||||||
|
if (ret > 0) {
|
||||||
|
total_bytes_read += ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
} else {
|
||||||
|
PX4_ERR("Got a poll error");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return total_bytes_read;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot write to serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int written = ::write(_serial_fd, buffer, buffer_size);
|
||||||
|
::fsync(_serial_fd);
|
||||||
|
|
||||||
|
if (written < 0) {
|
||||||
|
PX4_ERR("%s write error %d", _port, written);
|
||||||
|
}
|
||||||
|
|
||||||
|
return written;
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *SerialImpl::getPort() const
|
||||||
|
{
|
||||||
|
return _port;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t SerialImpl::getBaudrate() const
|
||||||
|
{
|
||||||
|
return _baudrate;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::setBaudrate(uint32_t baudrate)
|
||||||
|
{
|
||||||
|
// check if already configured
|
||||||
|
if (baudrate == _baudrate) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
_baudrate = baudrate;
|
||||||
|
|
||||||
|
// process baud rate change now if port is already open
|
||||||
|
if ((_open) && (configure() != 0)) {
|
||||||
|
// Configure failed! Close the port
|
||||||
|
close();
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::getSBUSMode() const
|
||||||
|
{
|
||||||
|
return _SBUSMode;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::setSBUSMode(bool enable)
|
||||||
|
{
|
||||||
|
if (_open) {
|
||||||
|
PX4_ERR("Cannot configure SBUS mode after port has already been opened");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
_SBUSMode = enable;
|
||||||
|
_baudrate = DEFAULT_SBUS_BAUDRATE;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,83 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
class SerialImpl
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
SerialImpl(const char *port, uint32_t baudrate);
|
||||||
|
virtual ~SerialImpl();
|
||||||
|
|
||||||
|
bool open();
|
||||||
|
bool isOpen() const;
|
||||||
|
|
||||||
|
bool close();
|
||||||
|
|
||||||
|
ssize_t read(uint8_t *buffer, size_t buffer_size);
|
||||||
|
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
|
||||||
|
|
||||||
|
ssize_t write(const void *buffer, size_t buffer_size);
|
||||||
|
|
||||||
|
const char *getPort() const;
|
||||||
|
|
||||||
|
uint32_t getBaudrate() const;
|
||||||
|
bool setBaudrate(uint32_t baudrate);
|
||||||
|
|
||||||
|
bool getSBUSMode() const;
|
||||||
|
bool setSBUSMode(bool enable);
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
int _serial_fd{-1};
|
||||||
|
|
||||||
|
bool _open{false};
|
||||||
|
|
||||||
|
char _port[32] {};
|
||||||
|
|
||||||
|
uint32_t _baudrate{0};
|
||||||
|
|
||||||
|
bool _SBUSMode{false};
|
||||||
|
static const uint32_t DEFAULT_SBUS_BAUDRATE{100000};
|
||||||
|
|
||||||
|
bool configure();
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,253 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include "SerialImpl.hpp"
|
||||||
|
|
||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <string.h> // strncpy
|
||||||
|
#include <px4_log.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <poll.h>
|
||||||
|
#include <drivers/drv_hrt.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
SerialImpl::SerialImpl(const char *port, uint32_t baudrate)
|
||||||
|
{
|
||||||
|
if (port) {
|
||||||
|
strncpy(_port, port, sizeof(_port) - 1);
|
||||||
|
_port[sizeof(_port) - 1] = '\0';
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_port[0] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (baudrate) {
|
||||||
|
_baudrate = baudrate;
|
||||||
|
} else {
|
||||||
|
// If baudrate is zero then choose a reasonable default
|
||||||
|
_baudrate = 9600;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
SerialImpl::~SerialImpl()
|
||||||
|
{
|
||||||
|
if (isOpen()) {
|
||||||
|
close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::configure()
|
||||||
|
{
|
||||||
|
if (_SBUSMode) {
|
||||||
|
return _sbus.configure(_serial_fd, _baudrate);
|
||||||
|
}
|
||||||
|
|
||||||
|
return _standard.configure(_serial_fd, _baudrate);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::open()
|
||||||
|
{
|
||||||
|
if (isOpen()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Open the serial port
|
||||||
|
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
|
||||||
|
|
||||||
|
if (serial_fd < 0) {
|
||||||
|
PX4_ERR("failed to open %s err: %d", _port, errno);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
_serial_fd = serial_fd;
|
||||||
|
|
||||||
|
// Configure the serial port
|
||||||
|
if (! configure()) {
|
||||||
|
PX4_ERR("failed to configure %s err: %d", _port, errno);
|
||||||
|
close();
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
_open = true;
|
||||||
|
|
||||||
|
return _open;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::isOpen() const
|
||||||
|
{
|
||||||
|
return _open;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::close()
|
||||||
|
{
|
||||||
|
if (_serial_fd >= 0) {
|
||||||
|
::close(_serial_fd);
|
||||||
|
}
|
||||||
|
|
||||||
|
_serial_fd = -1;
|
||||||
|
_open = false;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot read from serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int ret = ::read(_serial_fd, buffer, buffer_size);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
PX4_DEBUG("%s read error %d", _port, ret);
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (buffer_size < character_count) {
|
||||||
|
PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
const hrt_abstime start_time_us = hrt_absolute_time();
|
||||||
|
int total_bytes_read = 0;
|
||||||
|
|
||||||
|
while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) {
|
||||||
|
// Poll for incoming UART data.
|
||||||
|
pollfd fds[1];
|
||||||
|
fds[0].fd = _serial_fd;
|
||||||
|
fds[0].events = POLLIN;
|
||||||
|
|
||||||
|
hrt_abstime remaining_time = timeout_us - hrt_elapsed_time(&start_time_us);
|
||||||
|
|
||||||
|
if (remaining_time <= 0) { break; }
|
||||||
|
|
||||||
|
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), remaining_time);
|
||||||
|
|
||||||
|
if (ret > 0) {
|
||||||
|
if (fds[0].revents & POLLIN) {
|
||||||
|
ret = read(&buffer[total_bytes_read], buffer_size - total_bytes_read);
|
||||||
|
|
||||||
|
if (ret > 0) {
|
||||||
|
total_bytes_read += ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
} else {
|
||||||
|
PX4_ERR("Got a poll error");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return total_bytes_read;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot write to serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int written = ::write(_serial_fd, buffer, buffer_size);
|
||||||
|
::fsync(_serial_fd);
|
||||||
|
|
||||||
|
if (written < 0) {
|
||||||
|
PX4_ERR("%s write error %d", _port, written);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return written;
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *SerialImpl::getPort() const
|
||||||
|
{
|
||||||
|
return _port;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t SerialImpl::getBaudrate() const
|
||||||
|
{
|
||||||
|
return _baudrate;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::setBaudrate(uint32_t baudrate)
|
||||||
|
{
|
||||||
|
// check if already configured
|
||||||
|
if (baudrate == _baudrate) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
_baudrate = baudrate;
|
||||||
|
|
||||||
|
// process baud rate change now if port is already open
|
||||||
|
if ((_open) && (configure() != 0)) {
|
||||||
|
// Configure failed! Close the port
|
||||||
|
close();
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::getSBUSMode() const
|
||||||
|
{
|
||||||
|
return _SBUSMode;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::setSBUSMode(bool enable)
|
||||||
|
{
|
||||||
|
if (_open) {
|
||||||
|
PX4_ERR("Cannot configure SBUS mode after port has already been opened");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
_SBUSMode = enable;
|
||||||
|
_baudrate = SerialSBUSImpl::DEFAULT_BAUDRATE;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,89 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "SerialSBUSImpl.hpp"
|
||||||
|
#include "SerialStandardImpl.hpp"
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
class SerialImpl
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
SerialImpl(const char *port, uint32_t baudrate);
|
||||||
|
virtual ~SerialImpl();
|
||||||
|
|
||||||
|
bool open();
|
||||||
|
bool isOpen() const;
|
||||||
|
|
||||||
|
bool close();
|
||||||
|
|
||||||
|
ssize_t read(uint8_t *buffer, size_t buffer_size);
|
||||||
|
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
|
||||||
|
|
||||||
|
ssize_t write(const void *buffer, size_t buffer_size);
|
||||||
|
|
||||||
|
const char *getPort() const;
|
||||||
|
|
||||||
|
uint32_t getBaudrate() const;
|
||||||
|
bool setBaudrate(uint32_t baudrate);
|
||||||
|
|
||||||
|
bool getSBUSMode() const;
|
||||||
|
bool setSBUSMode(bool enable);
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
int _serial_fd{-1};
|
||||||
|
|
||||||
|
bool _open{false};
|
||||||
|
|
||||||
|
char _port[32] {};
|
||||||
|
|
||||||
|
uint32_t _baudrate{0};
|
||||||
|
|
||||||
|
bool _SBUSMode{false};
|
||||||
|
|
||||||
|
// The configuration routines for SBUS versus other needed to be separated
|
||||||
|
// out because they use different methods with different, conflicting header files
|
||||||
|
SerialSBUSImpl _sbus;
|
||||||
|
SerialStandardImpl _standard;
|
||||||
|
|
||||||
|
bool configure();
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,80 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include "SerialSBUSImpl.hpp"
|
||||||
|
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
#include <asm-generic/termbits.h>
|
||||||
|
#include <px4_log.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
bool SerialSBUSImpl::configure(int fd, uint32_t baud)
|
||||||
|
{
|
||||||
|
struct termios2 tio = {};
|
||||||
|
|
||||||
|
if (ioctl(fd, TCGETS2, &tio)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (baud != DEFAULT_BAUDRATE) {
|
||||||
|
PX4_WARN("Warning, SBUS baud rate being set to %u", baud);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Setting serial port,8E2, non-blocking.100Kbps
|
||||||
|
*/
|
||||||
|
tio.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL
|
||||||
|
| IXON);
|
||||||
|
tio.c_iflag |= (INPCK | IGNPAR);
|
||||||
|
tio.c_oflag &= ~OPOST;
|
||||||
|
tio.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
|
||||||
|
tio.c_cflag &= ~(CSIZE | CRTSCTS | PARODD | CBAUD);
|
||||||
|
/**
|
||||||
|
* use BOTHER to specify speed directly in c_[io]speed member
|
||||||
|
*/
|
||||||
|
tio.c_cflag |= (CS8 | CSTOPB | CLOCAL | PARENB | BOTHER | CREAD);
|
||||||
|
tio.c_ispeed = baud;
|
||||||
|
tio.c_ospeed = baud;
|
||||||
|
tio.c_cc[VMIN] = 25;
|
||||||
|
tio.c_cc[VTIME] = 0;
|
||||||
|
|
||||||
|
if (ioctl(fd, TCSETS2, &tio)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,53 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
class SerialSBUSImpl
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
SerialSBUSImpl() {};
|
||||||
|
virtual ~SerialSBUSImpl() {};
|
||||||
|
|
||||||
|
bool configure(int fd, uint32_t baud);
|
||||||
|
|
||||||
|
static const uint32_t DEFAULT_BAUDRATE{100000};
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,159 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include "SerialStandardImpl.hpp"
|
||||||
|
|
||||||
|
#include <sys/termios.h>
|
||||||
|
#include <px4_log.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
bool SerialStandardImpl::validateBaudrate(uint32_t baudrate)
|
||||||
|
{
|
||||||
|
return ((baudrate == 9600) ||
|
||||||
|
(baudrate == 19200) ||
|
||||||
|
(baudrate == 38400) ||
|
||||||
|
(baudrate == 57600) ||
|
||||||
|
(baudrate == 115200) ||
|
||||||
|
(baudrate == 230400) ||
|
||||||
|
(baudrate == 460800) ||
|
||||||
|
(baudrate == 921600));
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialStandardImpl::configure(int fd, uint32_t baud)
|
||||||
|
{
|
||||||
|
/* process baud rate */
|
||||||
|
int speed;
|
||||||
|
|
||||||
|
if (! validateBaudrate(baud)) {
|
||||||
|
PX4_ERR("ERR: unknown baudrate: %u", baud);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (baud) {
|
||||||
|
case 9600: speed = B9600; break;
|
||||||
|
|
||||||
|
case 19200: speed = B19200; break;
|
||||||
|
|
||||||
|
case 38400: speed = B38400; break;
|
||||||
|
|
||||||
|
case 57600: speed = B57600; break;
|
||||||
|
|
||||||
|
case 115200: speed = B115200; break;
|
||||||
|
|
||||||
|
case 230400: speed = B230400; break;
|
||||||
|
|
||||||
|
#ifndef B460800
|
||||||
|
#define B460800 460800
|
||||||
|
#endif
|
||||||
|
|
||||||
|
case 460800: speed = B460800; break;
|
||||||
|
|
||||||
|
#ifndef B921600
|
||||||
|
#define B921600 921600
|
||||||
|
#endif
|
||||||
|
|
||||||
|
case 921600: speed = B921600; break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
PX4_ERR("ERR: unknown baudrate: %d", baud);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
struct termios uart_config;
|
||||||
|
|
||||||
|
int termios_state;
|
||||||
|
|
||||||
|
/* fill the struct for the new configuration */
|
||||||
|
if ((termios_state = tcgetattr(fd, &uart_config)) < 0) {
|
||||||
|
PX4_ERR("ERR: %d (tcgetattr)", termios_state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */
|
||||||
|
|
||||||
|
//
|
||||||
|
// Input flags - Turn off input processing
|
||||||
|
//
|
||||||
|
// convert break to null byte, no CR to NL translation,
|
||||||
|
// no NL to CR translation, don't mark parity errors or breaks
|
||||||
|
// no input parity check, don't strip high bit off,
|
||||||
|
// no XON/XOFF software flow control
|
||||||
|
//
|
||||||
|
uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
|
||||||
|
INLCR | PARMRK | INPCK | ISTRIP | IXON);
|
||||||
|
|
||||||
|
//
|
||||||
|
// Output flags - Turn off output processing
|
||||||
|
//
|
||||||
|
// no CR to NL translation, no NL to CR-NL translation,
|
||||||
|
// no NL to CR translation, no column 0 CR suppression,
|
||||||
|
// no Ctrl-D suppression, no fill characters, no case mapping,
|
||||||
|
// no local output processing
|
||||||
|
//
|
||||||
|
// config.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
|
||||||
|
// ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
|
||||||
|
uart_config.c_oflag = 0;
|
||||||
|
|
||||||
|
//
|
||||||
|
// No line processing
|
||||||
|
//
|
||||||
|
// echo off, echo newline off, canonical mode off,
|
||||||
|
// extended input processing off, signal chars off
|
||||||
|
//
|
||||||
|
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
|
||||||
|
|
||||||
|
/* no parity, one stop bit, disable flow control */
|
||||||
|
uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS);
|
||||||
|
|
||||||
|
/* set baud rate */
|
||||||
|
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
|
||||||
|
PX4_ERR("ERR: %d (cfsetispeed)", termios_state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
|
||||||
|
PX4_ERR("ERR: %d (cfsetospeed)", termios_state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
|
||||||
|
PX4_ERR("ERR: %d (tcsetattr)", termios_state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,55 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
class SerialStandardImpl
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
SerialStandardImpl() {};
|
||||||
|
virtual ~SerialStandardImpl() {};
|
||||||
|
|
||||||
|
bool configure(int fd, uint32_t baud);
|
||||||
|
|
||||||
|
private:
|
||||||
|
bool validateBaudrate(uint32_t baudrate);
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,239 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include "SerialImpl.hpp"
|
||||||
|
#include <string.h> // strncpy
|
||||||
|
#include <px4_log.h>
|
||||||
|
#include <drivers/device/qurt/uart.h>
|
||||||
|
#include <drivers/drv_hrt.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
SerialImpl::SerialImpl(const char *port, uint32_t baudrate)
|
||||||
|
{
|
||||||
|
if (port) {
|
||||||
|
strncpy(_port, port, sizeof(_port) - 1);
|
||||||
|
_port[sizeof(_port) - 1] = '\0';
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_port[0] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (baudrate) {
|
||||||
|
_baudrate = baudrate;
|
||||||
|
} else {
|
||||||
|
// If baudrate is zero then choose a reasonable default.
|
||||||
|
// The default is the GPS UBX M10 default rate.
|
||||||
|
_baudrate = 115200;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
SerialImpl::~SerialImpl()
|
||||||
|
{
|
||||||
|
if (isOpen()) {
|
||||||
|
close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::open()
|
||||||
|
{
|
||||||
|
// There's no harm in calling open multiple times on the same port.
|
||||||
|
// In fact, that's the only way to change the baudrate
|
||||||
|
|
||||||
|
_open = false;
|
||||||
|
_serial_fd = -1;
|
||||||
|
|
||||||
|
// qurt_uart_open will check validity of port and baudrate
|
||||||
|
int serial_fd = qurt_uart_open(_port, _baudrate);
|
||||||
|
|
||||||
|
if (serial_fd < 0) {
|
||||||
|
PX4_ERR("failed to open %s at baudrate %u, fd: %d", _port, _baudrate, serial_fd);
|
||||||
|
close();
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
PX4_INFO("Successfully opened UART %s with baudrate %u", _port, _baudrate);
|
||||||
|
}
|
||||||
|
|
||||||
|
_serial_fd = serial_fd;
|
||||||
|
_open = true;
|
||||||
|
|
||||||
|
return _open;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::isOpen() const
|
||||||
|
{
|
||||||
|
return _open;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::close()
|
||||||
|
{
|
||||||
|
// No close defined for qurt uart yet
|
||||||
|
// if (_serial_fd >= 0) {
|
||||||
|
// qurt_uart_close(_serial_fd);
|
||||||
|
// }
|
||||||
|
|
||||||
|
_serial_fd = -1;
|
||||||
|
_open = false;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot read from serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 500);
|
||||||
|
|
||||||
|
if (ret_read < 0) {
|
||||||
|
PX4_DEBUG("%s read error %d", _port, ret_read);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret_read;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (buffer_size < character_count) {
|
||||||
|
PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
const hrt_abstime start_time_us = hrt_absolute_time();
|
||||||
|
int total_bytes_read = 0;
|
||||||
|
|
||||||
|
while (total_bytes_read < (int) character_count) {
|
||||||
|
|
||||||
|
if (timeout_us > 0) {
|
||||||
|
const uint64_t elapsed_us = hrt_elapsed_time(&start_time_us);
|
||||||
|
|
||||||
|
if (elapsed_us >= timeout_us) {
|
||||||
|
// If there was a partial read but not enough to satisfy the minimum then they will be lost
|
||||||
|
// but this really should never happen when everything is working normally.
|
||||||
|
// PX4_WARN("%s timeout %d bytes read (%llu us elapsed)", __FUNCTION__, total_bytes_read, elapsed_us);
|
||||||
|
// Or, instead of returning an error, should we return the number of bytes read (assuming it is greater than zero)?
|
||||||
|
return total_bytes_read;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int current_bytes_read = read(&buffer[total_bytes_read], buffer_size - total_bytes_read);
|
||||||
|
|
||||||
|
if (current_bytes_read < 0) {
|
||||||
|
// Again, if there was a partial read but not enough to satisfy the minimum then they will be lost
|
||||||
|
// but this really should never happen when everything is working normally.
|
||||||
|
PX4_ERR("%s failed to read uart", __FUNCTION__);
|
||||||
|
// Or, instead of returning an error, should we return the number of bytes read (assuming it is greater than zero)?
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Current bytes read could be zero
|
||||||
|
total_bytes_read += current_bytes_read;
|
||||||
|
|
||||||
|
// If we have at least reached our desired minimum number of characters
|
||||||
|
// then we can return now
|
||||||
|
if (total_bytes_read >= (int) character_count) {
|
||||||
|
return total_bytes_read;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Wait a set amount of time before trying again or the remaining time
|
||||||
|
// until the timeout if we are getting close
|
||||||
|
const uint64_t elapsed_us = hrt_elapsed_time(&start_time_us);
|
||||||
|
int64_t time_until_timeout = timeout_us - elapsed_us;
|
||||||
|
uint64_t time_to_sleep = 5000;
|
||||||
|
|
||||||
|
if ((time_until_timeout >= 0) &&
|
||||||
|
(time_until_timeout < (int64_t) time_to_sleep)) {
|
||||||
|
time_to_sleep = time_until_timeout;
|
||||||
|
}
|
||||||
|
|
||||||
|
px4_usleep(time_to_sleep);
|
||||||
|
}
|
||||||
|
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
|
||||||
|
{
|
||||||
|
if (!_open) {
|
||||||
|
PX4_ERR("Cannot write to serial device until it has been opened");
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int ret_write = qurt_uart_write(_serial_fd, (const char *) buffer, buffer_size);
|
||||||
|
|
||||||
|
if (ret_write < 0) {
|
||||||
|
PX4_ERR("%s write error %d", _port, ret_write);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret_write;
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *SerialImpl::getPort() const
|
||||||
|
{
|
||||||
|
return _port;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t SerialImpl::getBaudrate() const
|
||||||
|
{
|
||||||
|
return _baudrate;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool SerialImpl::setBaudrate(uint32_t baudrate)
|
||||||
|
{
|
||||||
|
// check if already configured
|
||||||
|
if (baudrate == _baudrate) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
_baudrate = baudrate;
|
||||||
|
|
||||||
|
// process baud rate change now if port is already open
|
||||||
|
if (_open) {
|
||||||
|
return open();
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace device
|
|
@ -0,0 +1,80 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
namespace device
|
||||||
|
{
|
||||||
|
|
||||||
|
class SerialImpl
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
SerialImpl(const char *port, uint32_t baudrate);
|
||||||
|
virtual ~SerialImpl();
|
||||||
|
|
||||||
|
bool open();
|
||||||
|
bool isOpen() const;
|
||||||
|
|
||||||
|
bool close();
|
||||||
|
|
||||||
|
ssize_t read(uint8_t *buffer, size_t buffer_size);
|
||||||
|
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
|
||||||
|
|
||||||
|
ssize_t write(const void *buffer, size_t buffer_size);
|
||||||
|
|
||||||
|
const char *getPort() const;
|
||||||
|
|
||||||
|
uint32_t getBaudrate() const;
|
||||||
|
bool setBaudrate(uint32_t baudrate);
|
||||||
|
|
||||||
|
// Cannot configure Qurt UARTs for SBUS!
|
||||||
|
bool getSBUSMode() const { return false; }
|
||||||
|
bool setSBUSMode(bool enable) { return false; }
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
int _serial_fd{-1};
|
||||||
|
|
||||||
|
bool _open{false};
|
||||||
|
|
||||||
|
char _port[32] {};
|
||||||
|
|
||||||
|
uint32_t _baudrate{0};
|
||||||
|
|
||||||
|
bool validateBaudrate(uint32_t baudrate);
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace device
|
Loading…
Reference in New Issue