Skip to content

Commit 3f1279b

Browse files
committed
Add support for ednging 'sololink'-style UDP packets
no actually used in ArduPilot for Solo, but is used in intel aero.
1 parent 53be06e commit 3f1279b

File tree

3 files changed

+32
-1
lines changed

3 files changed

+32
-1
lines changed

Diff for: MAVProxy/mavproxy.py

+6
Original file line numberDiff line numberDiff line change
@@ -335,6 +335,8 @@ def __init__(self):
335335

336336
# SITL output
337337
self.sitl_output = None
338+
# "sololink" (used by intel aero) UDP RC protocol
339+
self.rc_sololink_output = None
338340

339341
self.mav_param_by_sysid = {}
340342
self.mav_param_by_sysid[(self.settings.target_system, self.settings.target_component)] = mavparm.MAVParmDict()
@@ -1318,6 +1320,7 @@ def run_startup_scripts():
13181320
parser.add_option("--baudrate", dest="baudrate", type='int',
13191321
help="default serial baud rate", default=57600)
13201322
parser.add_option("--sitl", dest="sitl", default=None, help="SITL output port")
1323+
parser.add_option("--rc-sololink", dest="rc_sololink", default=None, help="Connection string for 'SoloLink'-style UDP RC")
13211324
parser.add_option("--streamrate", dest="streamrate", default=4, type='int',
13221325
help="MAVLink stream rate")
13231326
parser.add_option("--source-system", dest='SOURCE_SYSTEM', type='int',
@@ -1508,6 +1511,9 @@ def quit_handler(signum=None, frame=None):
15081511
if opts.sitl:
15091512
mpstate.sitl_output = mavutil.mavudp(opts.sitl, input=False)
15101513

1514+
if opts.rc_sololink:
1515+
mpstate.rc_sololink_output = mavutil.mavudp(opts.rc_sololink, input=False)
1516+
15111517
mpstate.settings.streamrate = opts.streamrate
15121518
mpstate.settings.streamrate2 = opts.streamrate
15131519

Diff for: MAVProxy/modules/lib/mp_module.py

+4
Original file line numberDiff line numberDiff line change
@@ -112,6 +112,10 @@ def vehicle_name(self):
112112
def sitl_output(self):
113113
return self.mpstate.sitl_output
114114

115+
@property
116+
def rc_sololink_output(self):
117+
return self.mpstate.rc_sololink_output
118+
115119
@property
116120
def target_system(self):
117121
return self.settings.target_system

Diff for: MAVProxy/modules/mavproxy_rc.py

+22-1
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77

88
import struct
99
import sys
10+
import time
1011

1112
from pymavlink import mavutil
1213
from MAVProxy.modules.lib import mp_module
@@ -40,6 +41,8 @@ def __init__(self, mpstate):
4041
self.rcin_gui = None
4142
self.init_gui_menus()
4243

44+
self.rc_sololink_oputput_seq = 0
45+
4346
def init_gui_menus(self):
4447
'''initialise menus for console'''
4548
self.menu_added_console = False
@@ -112,11 +115,29 @@ def mavlink_packet(self, m):
112115

113116
def send_rc(self):
114117
'''send RC override packet'''
118+
sent : bool = False
115119
if self.sitl_output:
116120
chan16 = self.override[:16]
117121
buf = struct.pack('<HHHHHHHHHHHHHHHH', *chan16)
118122
self.sitl_output.write(buf)
119-
else:
123+
sent = True
124+
125+
if self.rc_sololink_output:
126+
chan8 = self.override[:8]
127+
# this is the inverse of a transform done to the inputs by
128+
# SoloLink backend:
129+
tmp0 = chan8[0]
130+
chan8[0] = chan8[2]
131+
chan8[2] = chan8[1]
132+
chan8[1] = tmp0
133+
buf = struct.pack('<QHHHHHHHHH', int(time.time()*1000000), self.rc_sololink_oputput_seq, *chan8)
134+
self.rc_sololink_oputput_seq += 1
135+
if self.rc_sololink_oputput_seq > 65535:
136+
self.rc_sololink_oputput_seq = 0
137+
self.rc_sololink_output.write(buf)
138+
sent = True
139+
140+
if not sent:
120141
chan18 = self.override[:18]
121142
self.master.mav.rc_channels_override_send(self.target_system,
122143
self.target_component,

0 commit comments

Comments
 (0)