HAL_Linux: added bcast flag for udp broadcast

This commit is contained in:
Andrew Tridgell 2015-07-29 16:46:53 +10:00
parent eca0940bc7
commit 45a7c37734
3 changed files with 27 additions and 8 deletions

View File

@ -264,7 +264,8 @@ bool LinuxUARTDriver::_serial_start_connection()
*/ */
void LinuxUARTDriver::_udp_start_connection(void) void LinuxUARTDriver::_udp_start_connection(void)
{ {
_device = new UDPDevice(_ip, _base_port); bool bcast = (_flag && strcmp(_flag, "bcast") == 0);
_device = new UDPDevice(_ip, _base_port, bcast);
_connected = _device->open(); _connected = _device->open();
_device->set_blocking(false); _device->set_blocking(false);

View File

@ -8,15 +8,15 @@
#include "UDPDevice.h" #include "UDPDevice.h"
UDPDevice::UDPDevice(const char *ip, uint16_t port): UDPDevice::UDPDevice(const char *ip, uint16_t port, bool bcast):
_ip(ip), _ip(ip),
_port(port) _port(port),
_bcast(bcast)
{ {
} }
UDPDevice::~UDPDevice() UDPDevice::~UDPDevice()
{ {
} }
ssize_t UDPDevice::write(const uint8_t *buf, uint16_t n) ssize_t UDPDevice::write(const uint8_t *buf, uint16_t n)
@ -24,17 +24,33 @@ ssize_t UDPDevice::write(const uint8_t *buf, uint16_t n)
if (!socket.pollout(0)) { if (!socket.pollout(0)) {
return -1; return -1;
} }
if (_connected) {
return socket.send(buf, n); return socket.send(buf, n);
}
return socket.sendto(buf, n, _ip, _port);
} }
ssize_t UDPDevice::read(uint8_t *buf, uint16_t n) ssize_t UDPDevice::read(uint8_t *buf, uint16_t n)
{ {
return socket.recv(buf, n, 0); ssize_t ret = socket.recv(buf, n, 0);
if (!_connected && ret > 0) {
const char *ip;
uint16_t port;
socket.last_recv_address(ip, port);
_connected = socket.connect(ip, port);
}
return ret;
} }
bool UDPDevice::open() bool UDPDevice::open()
{ {
return socket.connect(_ip, _port); if (_bcast) {
// open now, then connect on first received packet
socket.set_broadcast();
return true;
}
_connected = socket.connect(_ip, _port);
return _connected;
} }
bool UDPDevice::close() bool UDPDevice::close()

View File

@ -6,7 +6,7 @@
class UDPDevice: public SerialDevice { class UDPDevice: public SerialDevice {
public: public:
UDPDevice(const char *ip, uint16_t port); UDPDevice(const char *ip, uint16_t port, bool bcast);
virtual ~UDPDevice(); virtual ~UDPDevice();
virtual bool open() override; virtual bool open() override;
@ -19,6 +19,8 @@ private:
SocketAPM socket{true}; SocketAPM socket{true};
const char *_ip; const char *_ip;
uint16_t _port; uint16_t _port;
bool _bcast;
bool _connected = false;
}; };
#endif #endif