APM:Libraries
TCPServerDevice.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "SerialDevice.h"
5 
7 public:
8  TCPServerDevice(const char *ip, uint16_t port, bool wait);
9  virtual ~TCPServerDevice();
10 
11  virtual bool open() override;
12  virtual bool close() override;
13  virtual void set_blocking(bool blocking) override;
14  virtual void set_speed(uint32_t speed) override;
15  virtual ssize_t write(const uint8_t *buf, uint16_t n) override;
16  virtual ssize_t read(uint8_t *buf, uint16_t n) override;
17 
18 private:
19  SocketAPM listener{false};
20  SocketAPM *sock = nullptr;
21  const char *_ip;
22  uint16_t _port;
23  bool _wait;
24  bool _blocking = false;
25  uint32_t _last_bind_warning = 0;
26 };
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
SocketAPM * sock
virtual ~TCPServerDevice()
const char * _ip
virtual void set_speed(uint32_t speed) override
SocketAPM listener
virtual bool close() override
virtual bool open() override
uint32_t _last_bind_warning
virtual ssize_t read(uint8_t *buf, uint16_t n) override