APM:Libraries
TCPServerDevice.cpp
Go to the documentation of this file.
1 #include "TCPServerDevice.h"
2 
3 #include <errno.h>
4 #include <stdio.h>
5 #include <stdlib.h>
6 #include <unistd.h>
7 
8 #include <AP_HAL/AP_HAL.h>
9 
10 extern const AP_HAL::HAL& hal;
11 
12 TCPServerDevice::TCPServerDevice(const char *ip, uint16_t port, bool wait):
13  _ip(ip),
14  _port(port),
15  _wait(wait)
16 {
17 }
18 
20 {
21  if (sock != nullptr) {
22  delete sock;
23  sock = nullptr;
24  }
25 }
26 
27 ssize_t TCPServerDevice::write(const uint8_t *buf, uint16_t n)
28 {
29  if (sock == nullptr) {
30  return -1;
31  }
32  return sock->send(buf, n);
33 }
34 
35 /*
36  when we try to read we accept new connections if one isn't already
37  established
38  */
39 ssize_t TCPServerDevice::read(uint8_t *buf, uint16_t n)
40 {
41  if (sock == nullptr) {
42  sock = listener.accept(0);
43  if (sock != nullptr) {
44  sock->set_blocking(_blocking);
45  }
46  }
47  if (sock == nullptr) {
48  return -1;
49  }
50  ssize_t ret = sock->recv(buf, n, 1);
51  if (ret == 0) {
52  // EOF, go back to waiting for a new connection
53  delete sock;
54  sock = nullptr;
55  return -1;
56  }
57  return ret;
58 }
59 
61 {
62  listener.reuseaddress();
63 
64  if (!listener.bind(_ip, _port)) {
65  if (AP_HAL::millis() - _last_bind_warning > 5000) {
66  ::printf("bind failed on %s port %u - %s\n",
67  _ip,
68  _port,
69  strerror(errno));
71  }
72  return false;
73  }
74 
75  if (!listener.listen(1)) {
76  if (AP_HAL::millis() - _last_bind_warning > 5000) {
77  ::printf("listen failed on %s port %u - %s\n",
78  _ip,
79  _port,
80  strerror(errno));
82  }
83  return false;
84  }
85 
86  listener.set_blocking(false);
87 
88  if (_wait) {
89  ::printf("Waiting for connection on %s:%u ....\n",
90  _ip, (unsigned)_port);
91  ::fflush(stdout);
92  while (sock == nullptr) {
93  sock = listener.accept(1000);
94  }
95  sock->set_blocking(_blocking);
96  ::printf("connected\n");
97  ::fflush(stdout);
98  }
99 
100  return true;
101 }
102 
104 {
105  if (sock != nullptr) {
106  delete sock;
107  sock = nullptr;
108  }
109  return true;
110 }
111 
112 void TCPServerDevice::set_blocking(bool blocking)
113 {
114  _blocking = blocking;
115  listener.set_blocking(_blocking);
116 }
117 
118 void TCPServerDevice::set_speed(uint32_t speed)
119 {
120 }
int printf(const char *fmt,...)
Definition: stdio.c:113
TCPServerDevice(const char *ip, uint16_t port, bool wait)
virtual ssize_t write(const uint8_t *buf, uint16_t n) override
virtual void set_blocking(bool blocking) override
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
SocketAPM * sock
virtual ~TCPServerDevice()
const char * _ip
uint32_t millis()
Definition: system.cpp:157
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual void set_speed(uint32_t speed) override
SocketAPM listener
virtual bool close() override
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
virtual bool open() override
uint32_t _last_bind_warning
virtual ssize_t read(uint8_t *buf, uint16_t n) override