mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: renamed TCPServerDevice
A more appropriate name for the class.
This commit is contained in:
parent
50765229ca
commit
39048229cd
|
@ -9,30 +9,30 @@
|
|||
#include <sys/socket.h>
|
||||
#include <netdb.h>
|
||||
|
||||
#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)
|
||||
{
|
||||
|
||||
}
|
|
@ -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;
|
|
@ -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);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue