|
1 | 1 | from __future__ import print_function
|
2 | 2 | import time
|
3 | 3 | import socket
|
| 4 | +import errno |
4 | 5 | import sys
|
5 | 6 | import os
|
6 | 7 | import platform
|
@@ -37,9 +38,85 @@ def read(self):
|
37 | 38 | os._exit(43)
|
38 | 39 |
|
39 | 40 |
|
| 41 | +class mavudpin_multi(mavutil.mavfile): |
| 42 | + '''a UDP mavlink socket''' |
| 43 | + def __init__(self, device, baud=None, input=True, broadcast=False, source_system=255, use_native=mavutil.default_native): |
| 44 | + a = device.split(':') |
| 45 | + if len(a) != 2: |
| 46 | + print("UDP ports must be specified as host:port") |
| 47 | + sys.exit(1) |
| 48 | + self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) |
| 49 | + self.udp_server = input |
| 50 | + self.broadcast = False |
| 51 | + self.addresses = set() |
| 52 | + if input: |
| 53 | + self.port.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) |
| 54 | + self.port.bind((a[0], int(a[1]))) |
| 55 | + else: |
| 56 | + self.destination_addr = (a[0], int(a[1])) |
| 57 | + if broadcast: |
| 58 | + self.port.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1) |
| 59 | + self.broadcast = True |
| 60 | + mavutil.set_close_on_exec(self.port.fileno()) |
| 61 | + self.port.setblocking(0) |
| 62 | + mavutil.mavfile.__init__(self, self.port.fileno(), device, source_system=source_system, input=input, use_native=use_native) |
| 63 | + |
| 64 | + def close(self): |
| 65 | + self.port.close() |
| 66 | + |
| 67 | + def recv(self,n=None): |
| 68 | + try: |
| 69 | + try: |
| 70 | + data, new_addr = self.port.recvfrom(65535) |
| 71 | + except socket.error as e: |
| 72 | + if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK, errno.ECONNREFUSED ]: |
| 73 | + return "" |
| 74 | + if self.udp_server: |
| 75 | + self.addresses.add(new_addr) |
| 76 | + elif self.broadcast: |
| 77 | + self.addresses = set([new_addr]) |
| 78 | + return data |
| 79 | + except Exception as e: |
| 80 | + print(e) |
| 81 | + |
| 82 | + def write(self, buf): |
| 83 | + try: |
| 84 | + try: |
| 85 | + if self.udp_server: |
| 86 | + for addr in self.addresses: |
| 87 | + self.port.sendto(buf, addr) |
| 88 | + else: |
| 89 | + if len(self.addresses) and self.broadcast: |
| 90 | + self.destination_addr = self.addresses[0] |
| 91 | + self.broadcast = False |
| 92 | + self.port.connect(self.destination_addr) |
| 93 | + self.port.sendto(buf, self.destination_addr) |
| 94 | + except socket.error: |
| 95 | + pass |
| 96 | + except Exception as e: |
| 97 | + print(e) |
| 98 | + |
| 99 | + def recv_msg(self): |
| 100 | + '''message receive routine for UDP link''' |
| 101 | + self.pre_message() |
| 102 | + s = self.recv() |
| 103 | + if len(s) > 0: |
| 104 | + if self.first_byte: |
| 105 | + self.auto_mavlink_version(s) |
| 106 | + |
| 107 | + m = self.mav.parse_char(s) |
| 108 | + if m is not None: |
| 109 | + self.post_message(m) |
| 110 | + |
| 111 | + return m |
| 112 | + |
| 113 | + |
40 | 114 | class MAVConnection(object):
|
41 | 115 | def __init__(self, ip, baud=115200, target_system=0, source_system=255, use_native=False):
|
42 |
| - self.master = mavutil.mavlink_connection(ip, baud=baud, source_system=source_system) |
| 116 | + if ip.startswith("udpin:"): |
| 117 | + self.master = mavudpin_multi(ip[6:], input=True, baud=baud, source_system=source_system) |
| 118 | + else: |
| 119 | + self.master = mavutil.mavlink_connection(ip, baud=baud, source_system=source_system) |
43 | 120 |
|
44 | 121 | # TODO get rid of "master" object as exposed,
|
45 | 122 | # keep it private, expose something smaller for dronekit
|
|
0 commit comments