AP_HAL_Linux: added UDPDevice

This commit is contained in:
Staroselskii Georgii 2015-06-16 00:01:14 +03:00 committed by Andrew Tridgell
parent 656399541f
commit 1881878c3a
2 changed files with 74 additions and 0 deletions

View File

@ -0,0 +1,50 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <stdio.h>
#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

View File

@ -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