From 1881878c3afa6d0b976e65a8a62c27c4146f7f40 Mon Sep 17 00:00:00 2001 From: Staroselskii Georgii Date: Tue, 16 Jun 2015 00:01:14 +0300 Subject: [PATCH] AP_HAL_Linux: added UDPDevice --- libraries/AP_HAL_Linux/UDPDevice.cpp | 50 ++++++++++++++++++++++++++++ libraries/AP_HAL_Linux/UDPDevice.h | 24 +++++++++++++ 2 files changed, 74 insertions(+) create mode 100644 libraries/AP_HAL_Linux/UDPDevice.cpp create mode 100644 libraries/AP_HAL_Linux/UDPDevice.h diff --git a/libraries/AP_HAL_Linux/UDPDevice.cpp b/libraries/AP_HAL_Linux/UDPDevice.cpp new file mode 100644 index 0000000000..265959ca78 --- /dev/null +++ b/libraries/AP_HAL_Linux/UDPDevice.cpp @@ -0,0 +1,50 @@ +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX + +#include + +#include "UDPDevice.h" + +UDPDevice::UDPDevice(const char *ip, uint16_t port): + _ip(ip), + _port(port) +{ +} + +UDPDevice::~UDPDevice() +{ + +} + +ssize_t UDPDevice::write(const uint8_t *buf, uint16_t n) +{ + return socket.sendto(buf, n, _ip, _port, 0); +} + +ssize_t UDPDevice::read(uint8_t *buf, uint16_t n) +{ + return socket.recvfrom(buf, n, 0); +} + +bool UDPDevice::open() +{ + return true; +} + +bool UDPDevice::close() +{ + return true; +} + +void UDPDevice::set_blocking(bool blocking) +{ + socket.set_blocking(blocking); +} + +void UDPDevice::set_speed(uint32_t speed) +{ + +} + +#endif diff --git a/libraries/AP_HAL_Linux/UDPDevice.h b/libraries/AP_HAL_Linux/UDPDevice.h new file mode 100644 index 0000000000..ac3a718cf0 --- /dev/null +++ b/libraries/AP_HAL_Linux/UDPDevice.h @@ -0,0 +1,24 @@ +#ifndef __AP_HAL_LINUX_UDPDEVICE_UDP_H__ +#define __AP_HAL_LINUX_UDPDEVICE_UDP_H__ + +#include "SerialDevice.h" +#include "../AP_HAL/utility/Socket.h" + +class UDPDevice: public SerialDevice { +public: + UDPDevice(const char *ip, uint16_t port); + virtual ~UDPDevice(); + + virtual bool open() override; + virtual bool close() override; + virtual void set_blocking(bool blocking) override; + virtual void set_speed(uint32_t speed) override; + virtual ssize_t write(const uint8_t *buf, uint16_t n) override; + virtual ssize_t read(uint8_t *buf, uint16_t n) override; +private: + SocketAPM socket{true}; + const char *_ip; + uint16_t _port; +}; + +#endif