Tools: remove references to legacy UART order

Also delete some unused variables and update the completions.
This commit is contained in:
Thomas Watson 2023-12-11 12:52:03 -06:00 committed by Andrew Tridgell
parent f6ea8201b2
commit de5b46e028
10 changed files with 63 additions and 57 deletions

View File

@ -3052,7 +3052,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
"""Disable GPS navigation, enable Vicon input."""
# scribble down a location we can set origin to:
self.customise_SITL_commandline(["--uartF=sim:vicon:"])
self.customise_SITL_commandline(["--serial5=sim:vicon:"])
self.progress("Waiting for location")
self.change_mode('LOITER')
self.wait_ready_to_arm()
@ -3153,7 +3153,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
# only tested on this EKF
return
self.customise_SITL_commandline(["--uartF=sim:vicon:"])
self.customise_SITL_commandline(["--serial5=sim:vicon:"])
if self.current_onboard_log_contains_message("XKFD"):
raise NotAchievedException("Found unexpected XKFD message")
@ -3293,7 +3293,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
def GPSViconSwitching(self):
"""Fly GPS and Vicon switching test"""
self.customise_SITL_commandline(["--uartF=sim:vicon:"])
self.customise_SITL_commandline(["--serial5=sim:vicon:"])
"""Setup parameters including switching to EKF3"""
self.context_push()
@ -7193,7 +7193,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.start_subtest("Testing %s" % name)
self.set_parameter("PRX1_TYPE", prx_type)
self.customise_SITL_commandline([
"--uartF=sim:%s:" % name,
"--serial5=sim:%s:" % name,
"--home", home_string,
])
self.wait_ready_to_arm()
@ -7630,7 +7630,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
})
self.reboot_sitl()
self.set_rc(9, 1000) # remember this is a switch position - stop
self.customise_SITL_commandline(["--uartF=sim:richenpower"])
self.customise_SITL_commandline(["--serial5=sim:richenpower"])
self.wait_statustext("requested state is not RUN", timeout=60)
self.set_message_rate_hz("GENERATOR_STATUS", 10)
@ -7697,7 +7697,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
"LOG_DISARMED": 1,
})
self.customise_SITL_commandline(["--uartF=sim:ie24"])
self.customise_SITL_commandline(["--serial5=sim:ie24"])
self.start_subtest("Protocol %i: ensure that BATTERY_STATUS for electrical generator message looks right" % proto_ver)
self.start_subsubtest("Protocol %i: Checking original voltage (electrical)" % proto_ver)
@ -8182,7 +8182,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
"SERIAL5_PROTOCOL": 1,
"RNGFND1_TYPE": 10,
})
self.customise_SITL_commandline(['--uartF=sim:rf_mavlink'])
self.customise_SITL_commandline(['--serial5=sim:rf_mavlink'])
self.change_mode('GUIDED')
self.wait_ready_to_arm()
@ -8329,17 +8329,16 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
drivers = drivers[3:]
command_line_args = []
self.context_push()
for (offs, cmdline_argument, serial_num) in [(0, '--uartE', 4),
(1, '--uartF', 5),
(2, '--uartG', 6)]:
for offs in range(3):
serial_num = offs + 4
if len(do_drivers) > offs:
if len(do_drivers[offs]) > 2:
(sim_name, rngfnd_param_value, kwargs) = do_drivers[offs]
else:
(sim_name, rngfnd_param_value) = do_drivers[offs]
kwargs = {}
command_line_args.append("%s=sim:%s" %
(cmdline_argument, sim_name))
command_line_args.append("--serial%s=sim:%s" %
(serial_num, sim_name))
sets = {
"SERIAL%u_PROTOCOL" % serial_num: 9, # rangefinder
"RNGFND%u_TYPE" % (offs+1): rngfnd_param_value,
@ -8380,7 +8379,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
"WPNAV_SPEED_UP": 1000, # cm/s
})
self.customise_SITL_commandline([
"--uartE=sim:lightwareserial",
"--serial4=sim:lightwareserial",
])
self.takeoff(95, mode='GUIDED', timeout=240, max_err=0.5)
self.assert_rangefinder_distance_between(90, 100)
@ -9776,7 +9775,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
"SERVO8_FUNCTION": 36,
"SIM_ESC_TELEM": 0,
})
self.customise_SITL_commandline(["--uartF=sim:fetteconewireesc"])
self.customise_SITL_commandline(["--serial5=sim:fetteconewireesc"])
self.FETtecESC_safety_switch()
self.FETtecESC_esc_power_checks()
self.FETtecESC_btw_mask_checks()
@ -10251,7 +10250,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
"PRX1_TYPE": 5,
})
self.customise_SITL_commandline([
"--uartF=sim:%s:" % sim_device_name,
"--serial5=sim:%s:" % sim_device_name,
"--home", "51.8752066,14.6487840,0,0", # SITL has "posts" here
])

View File

@ -3160,7 +3160,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
def fly_external_AHRS(self, sim, eahrs_type, mission):
"""Fly with external AHRS (VectorNav)"""
self.customise_SITL_commandline(["--uartE=sim:%s" % sim])
self.customise_SITL_commandline(["--serial4=sim:%s" % sim])
self.set_parameters({
"EAHRS_TYPE": eahrs_type,
@ -4218,7 +4218,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
})
self.customise_SITL_commandline(
["--uartF=sim:%s" % sim_name,
["--serial5=sim:%s" % sim_name,
],
)
self.wait_ready_to_arm()

View File

@ -539,7 +539,7 @@ def start_SITL(binary,
if unhide_parameters:
cmd.extend(['--unhide-groups'])
# somewhere for MAVProxy to connect to:
cmd.append('--uartC=tcp:2')
cmd.append('--serial1=tcp:2')
if not enable_fgview_output:
cmd.append("--disable-fgview")

View File

@ -6114,14 +6114,14 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
'''Test mulitple depthfinders for boats'''
# Setup rangefinders
self.customise_SITL_commandline([
"--uartH=sim:nmea", # NMEA Rangefinder
"--serial7=sim:nmea", # NMEA Rangefinder
])
# RANGEFINDER_INSTANCES = [0, 2, 5]
self.set_parameters({
"RNGFND1_TYPE" : 17, # NMEA must attach uart to SITL
"RNGFND1_ORIENT" : 25, # Set to downward facing
"SERIAL7_PROTOCOL" : 9, # Rangefinder on uartH
"SERIAL7_PROTOCOL" : 9, # Rangefinder on serial7
"SERIAL7_BAUD" : 9600, # Rangefinder specific baudrate
"RNGFND3_TYPE" : 2, # MaxbotixI2C

View File

@ -635,13 +635,13 @@ def run_in_terminal_window(name, cmd, **kw):
subprocess.Popen(runme, **kw)
tracker_uarta = None # blemish
tracker_serial0 = None # blemish
def start_antenna_tracker(opts):
"""Compile and run the AntennaTracker, add tracker to mavproxy"""
global tracker_uarta
global tracker_serial0
progress("Preparing antenna tracker")
tracker_home = find_location_by_name(opts.tracker_location)
vehicledir = os.path.join(autotest_dir, "../../" + "AntennaTracker")
@ -652,7 +652,7 @@ def start_antenna_tracker(opts):
tracker_instance = 1
oldpwd = os.getcwd()
os.chdir(vehicledir)
tracker_uarta = "tcp:127.0.0.1:" + str(5760 + 10 * tracker_instance)
tracker_serial0 = "tcp:127.0.0.1:" + str(5760 + 10 * tracker_instance)
binary_basedir = "build/sitl"
exe = os.path.join(root_dir,
binary_basedir,
@ -669,7 +669,6 @@ def start_antenna_tracker(opts):
def start_CAN_Periph(opts, frame_info):
"""Compile and run the sitl_periph"""
global can_uarta
progress("Preparing sitl_periph_gps")
options = vinfo.options["sitl_periph_gps"]['frames']['gps']
defaults_path = frame_info.get('periph_params_filename', None)
@ -838,9 +837,9 @@ def start_vehicle(binary, opts, stuff, spawns=None):
if spawns is not None:
c.extend(["--home", spawns[i]])
if opts.mcast:
c.extend(["--uartA", "mcast:"])
c.extend(["--serial0", "mcast:"])
elif opts.udp:
c.extend(["--uartA", "udpclient:127.0.0.1:" + str(5760+i*10)])
c.extend(["--serial0", "udpclient:127.0.0.1:" + str(5760+i*10)])
if opts.auto_sysid:
if opts.sysid is not None:
raise ValueError("Can't use auto-sysid and sysid together")
@ -901,12 +900,12 @@ def start_mavproxy(opts, stuff):
if opts.tracker:
cmd.extend(["--load-module", "tracker"])
global tracker_uarta
# tracker_uarta is set when we start the tracker...
global tracker_serial0
# tracker_serial0 is set when we start the tracker...
extra_cmd += ("module load map;"
"tracker set port %s; "
"tracker start; "
"tracker arm;" % (tracker_uarta,))
"tracker arm;" % (tracker_serial0,))
if opts.mavlink_gimbal:
cmd.extend(["--load-module", "gimbal"])

View File

@ -2942,7 +2942,7 @@ class TestSuite(ABC):
wipe=False,
set_streamrate_callback=None,
binary=None):
'''customisations could be "--uartF=sim:nmea" '''
'''customisations could be "--serial5=sim:nmea" '''
self.contexts[-1].sitl_commandline_customised = True
self.mav.close()
self.stop_SITL()
@ -11939,8 +11939,8 @@ switch value'''
self.set_parameter("GPS_TYPE2", 5) # GPS2 is NMEA
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartE=tcp:%u" % port, # GPS2 is NMEA....
"--uartF=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port
"--serial4=tcp:%u" % port, # GPS2 is NMEA....
"--serial5=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port
])
self.do_timesync_roundtrip()
self.wait_gps_fix_type_gte(3)
@ -12556,7 +12556,7 @@ switch value'''
})
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 spews to localhost port
"--serial5=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkyPassThrough(("127.0.0.1", port),
get_time=self.get_sim_time_cached)
@ -12647,7 +12647,7 @@ switch value'''
})
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 spews to localhost port
"--serial5=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkyPassThrough(("127.0.0.1", port),
get_time=self.get_sim_time_cached)
@ -12802,7 +12802,7 @@ switch value'''
self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 spews to localhost port
"--serial5=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkyPassThrough(("127.0.0.1", port))
frsky.connect()
@ -13077,7 +13077,7 @@ switch value'''
self.set_parameter("RPM1_TYPE", 10) # enable SITL RPM sensor
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 spews to localhost port
"--serial5=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkySPort(("127.0.0.1", port), verbose=True)
self.wait_ready_to_arm()
@ -13150,7 +13150,7 @@ switch value'''
self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 spews to localhost port
"--serial5=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkyD(("127.0.0.1", port))
self.wait_ready_to_arm()
@ -13269,7 +13269,7 @@ switch value'''
self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 spews to localhost port
"--serial5=tcp:%u" % port # serial5 spews to localhost port
])
ltm = LTM(("127.0.0.1", port))
self.wait_ready_to_arm()
@ -13312,7 +13312,7 @@ switch value'''
self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 spews to localhost port
"--serial5=tcp:%u" % port # serial5 spews to localhost port
])
devo = DEVO(("127.0.0.1", port))
self.wait_ready_to_arm()
@ -13385,7 +13385,7 @@ switch value'''
self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 spews to localhost port
"--serial5=tcp:%u" % port # serial5 spews to localhost port
])
msp = MSP_DJI(("127.0.0.1", port))
self.wait_ready_to_arm()
@ -13413,7 +13413,7 @@ switch value'''
self.set_parameter("SERIAL5_PROTOCOL", 23) # serial5 is RCIN input
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:%u" % port # serial5 reads from to localhost port
"--serial5=tcp:%u" % port # serial5 reads from to localhost port
])
crsf = CRSF(("127.0.0.1", port))
crsf.connect()

View File

@ -21,16 +21,26 @@ _ap_bin() {
'--gimbal[enable simulated MAVLink gimbal]' \
'--autotest-dir[set directory for additional files]:DIR:' \
'--defaults[set path to defaults file]:PATH:' \
'--uartA[set device string for UARTA]:DEVICE:' \
'--uartB[set device string for UARTB]:DEVICE:' \
'--uartC[set device string for UARTC]:DEVICE:' \
'--uartD[set device string for UARTD]:DEVICE:' \
'--uartE[set device string for UARTE]:DEVICE:' \
'--uartF[set device string for UARTF]:DEVICE:' \
'--uartG[set device string for UARTG]:DEVICE:' \
'--uartH[set device string for UARTH]:DEVICE:' \
'--uartI[set device string for UARTI]:DEVICE:' \
'--uartJ[set device string for UARTJ]:DEVICE:' \
'--uartA[set device string for SERIAL0]:DEVICE:' \
'--uartC[set device string for SERIAL1]:DEVICE:' \
'--uartD[set device string for SERIAL2]:DEVICE:' \
'--uartB[set device string for SERIAL3]:DEVICE:' \
'--uartE[set device string for SERIAL4]:DEVICE:' \
'--uartF[set device string for SERIAL5]:DEVICE:' \
'--uartG[set device string for SERIAL6]:DEVICE:' \
'--uartH[set device string for SERIAL7]:DEVICE:' \
'--uartI[set device string for SERIAL8]:DEVICE:' \
'--uartJ[set device string for SERIAL9]:DEVICE:' \
'--serial0[set device string for SERIAL0]:DEVICE:' \
'--serial1[set device string for SERIAL1]:DEVICE:' \
'--serial2[set device string for SERIAL2]:DEVICE:' \
'--serial3[set device string for SERIAL3]:DEVICE:' \
'--serial4[set device string for SERIAL4]:DEVICE:' \
'--serial5[set device string for SERIAL5]:DEVICE:' \
'--serial6[set device string for SERIAL6]:DEVICE:' \
'--serial7[set device string for SERIAL7]:DEVICE:' \
'--serial8[set device string for SERIAL8]:DEVICE:' \
'--serial9[set device string for SERIAL9]:DEVICE:' \
'--rtscts[enable rtscts on serial ports (default false)]' \
'--base-port[set port num for base port(default 5670) must be before -I option]:PORT:' \
'--rc-in-port[set port num for rc in]:PORT:' \

View File

@ -187,7 +187,7 @@ ros2 run micro_ros_agent micro_ros_agent serial --baudrate 115200 --dev ./dev/tt
```
```bash
arducopter --synthetic-clock --wipe --model quad --speedup 1 --slave 0 --instance 0 --uartC uart:./dev/ttyROS1 --defaults $(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm --sim-address 127.0.0.1
arducopter --synthetic-clock --wipe --model quad --speedup 1 --slave 0 --instance 0 --serial1 uart:./dev/ttyROS1 --defaults $(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm --sim-address 127.0.0.1
```
```bash
@ -205,7 +205,7 @@ ros2 launch ardupilot_sitl micro_ros_agent.launch.py transport:=serial refs:=$(r
```
```bash
ros2 launch ardupilot_sitl sitl.launch.py synthetic_clock:=True wipe:=True model:=quad speedup:=1 slave:=0 instance:=0 uartC:=uart:./dev/ttyROS1 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm sim_address:=127.0.0.1
ros2 launch ardupilot_sitl sitl.launch.py synthetic_clock:=True wipe:=True model:=quad speedup:=1 slave:=0 instance:=0 serial1:=uart:./dev/ttyROS1 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm sim_address:=127.0.0.1
```
```bash
@ -231,7 +231,7 @@ model:=quad \
speedup:=1 \
slave:=0 \
instance:=0 \
uartC:=uart:./dev/ttyROS1 \
serial1:=uart:./dev/ttyROS1 \
defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm \
sim_address:=127.0.0.1 \
\

View File

@ -145,7 +145,7 @@ def sitl_copter_dds_serial(device_dir, virtual_ports, micro_ros_agent_serial, ma
"speedup": "10",
"slave": "0",
"instance": "0",
"uartC": f"uart:{str(tty1)}",
"serial1": f"uart:{str(tty1)}",
"defaults": str(
Path(
get_package_share_directory("ardupilot_sitl"),

View File

@ -12,8 +12,6 @@
# rate: 400
# console: true
# home: [lat, lon, alt, yaw]
# uartA: /dev/tty0
# uartB: /dev/tty1
# serial0: /dev/usb0
# serial1: /dev/usb1
# sim_port_in: 5501