UDPDevice.cpp 1.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. #include "UDPDevice.h"
  2. #include <fcntl.h>
  3. #include <stdio.h>
  4. #include <sys/ioctl.h>
  5. #include <AP_HAL/AP_HAL.h>
  6. UDPDevice::UDPDevice(const char *ip, uint16_t port, bool bcast, bool input):
  7. _ip(ip),
  8. _port(port),
  9. _bcast(bcast),
  10. _input(input)
  11. {
  12. }
  13. UDPDevice::~UDPDevice()
  14. {
  15. }
  16. ssize_t UDPDevice::write(const uint8_t *buf, uint16_t n)
  17. {
  18. if (!socket.pollout(0)) {
  19. return -1;
  20. }
  21. if (_connected) {
  22. return socket.send(buf, n);
  23. }
  24. if (_input) {
  25. // can't send yet
  26. return -1;
  27. }
  28. return socket.sendto(buf, n, _ip, _port);
  29. }
  30. ssize_t UDPDevice::read(uint8_t *buf, uint16_t n)
  31. {
  32. ssize_t ret = socket.recv(buf, n, 0);
  33. if (!_connected && ret > 0) {
  34. const char *ip;
  35. uint16_t port;
  36. socket.last_recv_address(ip, port);
  37. _connected = socket.connect(ip, port);
  38. }
  39. return ret;
  40. }
  41. bool UDPDevice::open()
  42. {
  43. if (_input) {
  44. socket.bind(_ip, _port);
  45. return true;
  46. }
  47. if (_bcast) {
  48. // open now, then connect on first received packet
  49. socket.set_broadcast();
  50. return true;
  51. }
  52. _connected = socket.connect(_ip, _port);
  53. return _connected;
  54. }
  55. bool UDPDevice::close()
  56. {
  57. return true;
  58. }
  59. void UDPDevice::set_blocking(bool blocking)
  60. {
  61. socket.set_blocking(blocking);
  62. }
  63. void UDPDevice::set_speed(uint32_t speed)
  64. {
  65. }