From 6ec67a9bfd5f14dec39fe2c4c62ad0b1a3b8e8ae Mon Sep 17 00:00:00 2001 From: Staroselskii Georgii Date: Fri, 12 Jun 2015 00:31:50 +0300 Subject: [PATCH] AP_HAL_Linux: made UARTDriver use UDPDevice --- libraries/AP_HAL_Linux/UARTDriver.cpp | 47 ++++++--------------------- 1 file changed, 10 insertions(+), 37 deletions(-) diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index ec166a4802..8424ff03bb 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -25,6 +25,7 @@ #include "../AP_HAL/utility/RingBuffer.h" #include "UARTDevice.h" +#include "UDPDevice.h" extern const AP_HAL::HAL& hal; @@ -367,38 +368,11 @@ void LinuxUARTDriver::_tcp_start_connection(bool wait_for_connection) */ void LinuxUARTDriver::_udp_start_connection(void) { - struct sockaddr_in sockaddr; - int ret; - - memset(&sockaddr,0,sizeof(sockaddr)); + _device = new UDPDevice(_ip, _base_port); + _device->open(); + _device->set_blocking(false); -#ifdef HAVE_SOCK_SIN_LEN - sockaddr.sin_len = sizeof(sockaddr); -#endif - sockaddr.sin_port = htons(_base_port); - sockaddr.sin_family = AF_INET; - sockaddr.sin_addr.s_addr = inet_addr(_ip); - - _rd_fd = socket(AF_INET, SOCK_DGRAM, 0); - if (_rd_fd == -1) { - ::printf("socket failed - %s\n", strerror(errno)); - exit(1); - } - - ret = connect(_rd_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); - if (ret == -1) { - ::printf("connect failed to %s:%u - %s\n", - _ip, (unsigned)_base_port, - strerror(errno)); - exit(1); - } - - // always run the file descriptor non-blocking, and deal with | - // blocking IO in the higher level calls - fcntl(_rd_fd, F_SETFL, fcntl(_rd_fd, F_GETFL, 0) | O_NONBLOCK); - _wr_fd = _rd_fd; - - // try to write on MAVLink packet boundaries if possible + /* try to write on MAVLink packet boundaries if possible */ _packetise = true; } @@ -409,13 +383,12 @@ void LinuxUARTDriver::end() { _initialised = false; _connected = false; - while (_in_timer) hal.scheduler->delay(1); - if (_rd_fd == _wr_fd && _rd_fd != -1) { - _device->close(); - } - _rd_fd = -1; - _wr_fd = -1; + while (_in_timer) { + hal.scheduler->delay(1); + } + + _device->close(); _deallocate_buffers(); }