mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_HAL_Linux: move from HAL_NO_GCS to HAL_GCS_ENABLED
This commit is contained in:
parent
6ce79785b5
commit
275457fd2c
@ -25,15 +25,15 @@
|
|||||||
#include "UDPDevice.h"
|
#include "UDPDevice.h"
|
||||||
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
#include <AP_HAL/utility/packetise.h>
|
#include <AP_HAL/utility/packetise.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
UARTDriver::UARTDriver(bool default_console) :
|
UARTDriver::UARTDriver(bool default_console) :
|
||||||
device_path(nullptr),
|
|
||||||
_packetise(false),
|
|
||||||
_device{new ConsoleDevice()}
|
_device{new ConsoleDevice()}
|
||||||
{
|
{
|
||||||
if (default_console) {
|
if (default_console) {
|
||||||
@ -189,7 +189,9 @@ AP_HAL::OwnPtr<SerialDevice> UARTDriver::_parseDevicePath(const char *arg)
|
|||||||
|
|
||||||
if (strcmp(protocol, "udp") == 0 || strcmp(protocol, "udpin") == 0) {
|
if (strcmp(protocol, "udp") == 0 || strcmp(protocol, "udpin") == 0) {
|
||||||
bool bcast = (_flag && strcmp(_flag, "bcast") == 0);
|
bool bcast = (_flag && strcmp(_flag, "bcast") == 0);
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
_packetise = true;
|
_packetise = true;
|
||||||
|
#endif
|
||||||
if (strcmp(protocol, "udp") == 0) {
|
if (strcmp(protocol, "udp") == 0) {
|
||||||
device = new UDPDevice(_ip, _base_port, bcast, false);
|
device = new UDPDevice(_ip, _base_port, bcast, false);
|
||||||
} else {
|
} else {
|
||||||
@ -391,10 +393,12 @@ bool UARTDriver::_write_pending_bytes(void)
|
|||||||
uint32_t available_bytes = _writebuf.available();
|
uint32_t available_bytes = _writebuf.available();
|
||||||
uint16_t n = available_bytes;
|
uint16_t n = available_bytes;
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
if (_packetise && n > 0) {
|
if (_packetise && n > 0) {
|
||||||
// send on MAVLink packet boundaries if possible
|
// send on MAVLink packet boundaries if possible
|
||||||
n = mavlink_packetise(_writebuf, n);
|
n = mavlink_packetise(_writebuf, n);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (n > 0) {
|
if (n > 0) {
|
||||||
int ret;
|
int ret;
|
||||||
|
Loading…
Reference in New Issue
Block a user