AP_HAL_Linux: renamed TCPClientDevice

This commit is contained in:
Staroselskii Georgii 2015-07-08 20:27:21 +03:00 committed by Randy Mackay
parent 39048229cd
commit f66f583843
3 changed files with 15 additions and 15 deletions

View File

@ -7,30 +7,30 @@
#include <errno.h> #include <errno.h>
#include <stdlib.h> #include <stdlib.h>
#include "TCPClientDevice.h" #include "TCPServerDevice.h"
TCPClientDevice::TCPClientDevice(const char *ip, uint16_t port): TCPServerDevice::TCPServerDevice(const char *ip, uint16_t port):
_ip(ip), _ip(ip),
_port(port) _port(port)
{ {
} }
TCPClientDevice::~TCPClientDevice() TCPServerDevice::~TCPServerDevice()
{ {
} }
ssize_t TCPClientDevice::write(const uint8_t *buf, uint16_t n) ssize_t TCPServerDevice::write(const uint8_t *buf, uint16_t n)
{ {
return listener.send(buf, n); return listener.send(buf, n);
} }
ssize_t TCPClientDevice::read(uint8_t *buf, uint16_t n) ssize_t TCPServerDevice::read(uint8_t *buf, uint16_t n)
{ {
return listener.recv(buf, n, 1); return listener.recv(buf, n, 1);
} }
bool TCPClientDevice::open() bool TCPServerDevice::open()
{ {
listener.reuseaddress(); listener.reuseaddress();
@ -47,17 +47,17 @@ bool TCPClientDevice::open()
return true; return true;
} }
bool TCPClientDevice::close() bool TCPServerDevice::close()
{ {
return true; return true;
} }
void TCPClientDevice::set_blocking(bool blocking) void TCPServerDevice::set_blocking(bool blocking)
{ {
listener.set_blocking(blocking); listener.set_blocking(blocking);
} }
void TCPClientDevice::set_speed(uint32_t speed) void TCPServerDevice::set_speed(uint32_t speed)
{ {
} }

View File

@ -4,10 +4,10 @@
#include "SerialDevice.h" #include "SerialDevice.h"
#include "../AP_HAL/utility/Socket.h" #include "../AP_HAL/utility/Socket.h"
class TCPClientDevice: public SerialDevice { class TCPServerDevice: public SerialDevice {
public: public:
TCPClientDevice(const char *ip, uint16_t port); TCPServerDevice(const char *ip, uint16_t port);
virtual ~TCPClientDevice(); virtual ~TCPServerDevice();
virtual bool open() override; virtual bool open() override;
virtual bool close() override; virtual bool close() override;

View File

@ -27,7 +27,7 @@
#include "UARTDevice.h" #include "UARTDevice.h"
#include "UDPDevice.h" #include "UDPDevice.h"
#include "ConsoleDevice.h" #include "ConsoleDevice.h"
#include "TCPClientDevice.h" #include "TCPServerDevice.h"
#include "TCPBlockingServerDevice.h" #include "TCPBlockingServerDevice.h"
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -260,10 +260,10 @@ void LinuxUARTDriver::_tcp_start_connection(void)
if (!strcmp(_flag, "wait")) { if (!strcmp(_flag, "wait")) {
_device = new TCPBlockingServerDevice(_ip, _base_port); _device = new TCPBlockingServerDevice(_ip, _base_port);
} else { } else {
_device = new TCPClientDevice(_ip, _base_port); _device = new TCPServerDevice(_ip, _base_port);
} }
} else { } else {
_device = new TCPClientDevice(_ip, _base_port); _device = new TCPServerDevice(_ip, _base_port);
} }
if (_device->open()) { if (_device->open()) {