From 275457fd2cafa0f1525e4df3499c5235dc3f0d5c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 18 Sep 2021 09:48:29 +1000 Subject: [PATCH] AP_HAL_Linux: move from HAL_NO_GCS to HAL_GCS_ENABLED --- libraries/AP_HAL_Linux/UARTDriver.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index b5d59780db..83bb6edac3 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -25,15 +25,15 @@ #include "UDPDevice.h" #include +#if HAL_GCS_ENABLED #include +#endif extern const AP_HAL::HAL& hal; using namespace Linux; UARTDriver::UARTDriver(bool default_console) : - device_path(nullptr), - _packetise(false), _device{new ConsoleDevice()} { if (default_console) { @@ -189,7 +189,9 @@ AP_HAL::OwnPtr UARTDriver::_parseDevicePath(const char *arg) if (strcmp(protocol, "udp") == 0 || strcmp(protocol, "udpin") == 0) { bool bcast = (_flag && strcmp(_flag, "bcast") == 0); +#if HAL_GCS_ENABLED _packetise = true; +#endif if (strcmp(protocol, "udp") == 0) { device = new UDPDevice(_ip, _base_port, bcast, false); } else { @@ -391,10 +393,12 @@ bool UARTDriver::_write_pending_bytes(void) uint32_t available_bytes = _writebuf.available(); uint16_t n = available_bytes; +#if HAL_GCS_ENABLED if (_packetise && n > 0) { // send on MAVLink packet boundaries if possible n = mavlink_packetise(_writebuf, n); } +#endif if (n > 0) { int ret;