From 39048229cd40c5d1cc5b4bde67eabcdc37b10e61 Mon Sep 17 00:00:00 2001 From: Staroselskii Georgii Date: Wed, 8 Jul 2015 20:17:32 +0300 Subject: [PATCH] AP_HAL_Linux: renamed TCPServerDevice A more appropriate name for the class. --- ...Device.cpp => TCPBlockingServerDevice.cpp} | 20 +++++++++---------- ...rverDevice.h => TCPBlockingServerDevice.h} | 6 +++--- libraries/AP_HAL_Linux/UARTDriver.cpp | 4 ++-- 3 files changed, 15 insertions(+), 15 deletions(-) rename libraries/AP_HAL_Linux/{TCPServerDevice.cpp => TCPBlockingServerDevice.cpp} (83%) rename libraries/AP_HAL_Linux/{TCPServerDevice.h => TCPBlockingServerDevice.h} (78%) diff --git a/libraries/AP_HAL_Linux/TCPServerDevice.cpp b/libraries/AP_HAL_Linux/TCPBlockingServerDevice.cpp similarity index 83% rename from libraries/AP_HAL_Linux/TCPServerDevice.cpp rename to libraries/AP_HAL_Linux/TCPBlockingServerDevice.cpp index dac38dd618..22cf1233a7 100644 --- a/libraries/AP_HAL_Linux/TCPServerDevice.cpp +++ b/libraries/AP_HAL_Linux/TCPBlockingServerDevice.cpp @@ -9,30 +9,30 @@ #include #include -#include "TCPServerDevice.h" +#include "TCPBlockingServerDevice.h" -TCPServerDevice::TCPServerDevice(const char *ip, uint16_t port): +TCPBlockingServerDevice::TCPBlockingServerDevice(const char *ip, uint16_t port): _ip(ip), _port(port) { } -TCPServerDevice::~TCPServerDevice() +TCPBlockingServerDevice::~TCPBlockingServerDevice() { } -ssize_t TCPServerDevice::write(const uint8_t *buf, uint16_t n) +ssize_t TCPBlockingServerDevice::write(const uint8_t *buf, uint16_t n) { return ::send(_net_fd, buf, n, 0); } -ssize_t TCPServerDevice::read(uint8_t *buf, uint16_t n) +ssize_t TCPBlockingServerDevice::read(uint8_t *buf, uint16_t n) { return ::recv(_net_fd, buf, n, 0); } -bool TCPServerDevice::open() +bool TCPBlockingServerDevice::open() { int one=1; struct sockaddr_in sockaddr; @@ -87,7 +87,7 @@ bool TCPServerDevice::open() ::fflush(stdout); struct sockaddr_storage client_addr; - socklen_t addr_size; + socklen_t addr_size = sizeof(client_addr); client_fd = accept(_listen_fd, (struct sockaddr *) &client_addr, &addr_size); @@ -111,7 +111,7 @@ bool TCPServerDevice::open() return true; } -bool TCPServerDevice::close() +bool TCPBlockingServerDevice::close() { if (::close(_listen_fd) < 0) { perror("close"); @@ -126,11 +126,11 @@ bool TCPServerDevice::close() return true; } -void TCPServerDevice::set_blocking(bool blocking) +void TCPBlockingServerDevice::set_blocking(bool blocking) { } -void TCPServerDevice::set_speed(uint32_t speed) +void TCPBlockingServerDevice::set_speed(uint32_t speed) { } diff --git a/libraries/AP_HAL_Linux/TCPServerDevice.h b/libraries/AP_HAL_Linux/TCPBlockingServerDevice.h similarity index 78% rename from libraries/AP_HAL_Linux/TCPServerDevice.h rename to libraries/AP_HAL_Linux/TCPBlockingServerDevice.h index 50609e1dfc..07b70976d3 100644 --- a/libraries/AP_HAL_Linux/TCPServerDevice.h +++ b/libraries/AP_HAL_Linux/TCPBlockingServerDevice.h @@ -4,10 +4,10 @@ #include "SerialDevice.h" #include "../AP_HAL/utility/Socket.h" -class TCPServerDevice: public SerialDevice { +class TCPBlockingServerDevice: public SerialDevice { public: - TCPServerDevice(const char *ip, uint16_t port); - virtual ~TCPServerDevice(); + TCPBlockingServerDevice(const char *ip, uint16_t port); + virtual ~TCPBlockingServerDevice(); virtual bool open() override; virtual bool close() override; diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index c47825290e..35395dca9b 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -28,7 +28,7 @@ #include "UDPDevice.h" #include "ConsoleDevice.h" #include "TCPClientDevice.h" -#include "TCPServerDevice.h" +#include "TCPBlockingServerDevice.h" extern const AP_HAL::HAL& hal; @@ -258,7 +258,7 @@ void LinuxUARTDriver::_tcp_start_connection(void) { if (_flag != NULL) { if (!strcmp(_flag, "wait")) { - _device = new TCPServerDevice(_ip, _base_port); + _device = new TCPBlockingServerDevice(_ip, _base_port); } else { _device = new TCPClientDevice(_ip, _base_port); }