Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_HAL: clean up UART driver storage/access and legacy ordering #25589

Merged
merged 28 commits into from
Dec 18, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
3835b17
AP_HAL: use array of UART drivers instead of consecutive variables
tpwrules Nov 15, 2023
fe816cb
AP_HAL: move serial re-mapping to driver array initialization
tpwrules Nov 21, 2023
dbb32ff
AP_HAL: inline serial accessor function
tpwrules Nov 21, 2023
c0f2e03
AP_HAL: constructor now accepts UARTs in SERIALn order
tpwrules Dec 10, 2023
651bca6
AP_HAL: remove references to legacy UART order
tpwrules Dec 11, 2023
53e5893
AP_HAL_ChibiOS: pass UARTs to AP_HAL in SERIALn order
tpwrules Dec 10, 2023
a4571db
AP_HAL_Empty: pass UARTs to AP_HAL in SERIALn order
tpwrules Dec 10, 2023
32155f5
AP_HAL_ESP32: pass UARTs to AP_HAL in SERIALn order
tpwrules Dec 10, 2023
b62d197
AP_HAL_Linux: pass UARTs to AP_HAL in SERIALn order
tpwrules Dec 10, 2023
82bc8fc
AP_HAL_SITL: pass UARTs to AP_HAL in SERIALn order
tpwrules Dec 10, 2023
31f2cca
AP_HAL_ChibiOS: eliminate legacy UART ordering/references
tpwrules Dec 11, 2023
00ead24
AP_HAL_ChibiOS: remove references to legacy UART order from hwdefs
tpwrules Dec 11, 2023
8410432
AP_HAL_Empty: eliminate legacy UART ordering/references
tpwrules Dec 10, 2023
3a0f527
AP_HAL_ESP32: eliminate legacy UART ordering/references
tpwrules Dec 10, 2023
e70abad
AP_HAL_Linux: eliminate internal legacy UART ordering/references
tpwrules Dec 11, 2023
e22d651
AP_HAL_SITL: eliminate internal legacy UART ordering/references
tpwrules Dec 11, 2023
c136da1
SITL: remove references to legacy UART order incl. sim arguments
tpwrules Dec 11, 2023
13eecc2
Tools: remove references to legacy UART order
tpwrules Dec 11, 2023
4c42442
Tracker: remove references to legacy UART order
tpwrules Dec 11, 2023
087219d
Plane: remove references to legacy UART order
tpwrules Dec 11, 2023
2d7dea9
Rover: remove references to legacy UART order
tpwrules Dec 11, 2023
87a98e3
GCS_MAVLink: correct comment about stream array
tpwrules Dec 11, 2023
6d48866
AP_Scripting: remove references to legacy UART order
tpwrules Dec 11, 2023
aac2222
AP_DDS: remove references to legacy UART order
tpwrules Dec 11, 2023
080140f
AP_FETtecOneWire: remove references to legacy UART order
tpwrules Dec 11, 2023
bb5193c
AP_SerialManager: clarify comment regarding legacy UART order
tpwrules Dec 11, 2023
d78aa8b
AP_HAL_SITL: deprecate and warn on legacy --uartX option use
tpwrules Dec 12, 2023
037e00c
AP_HAL_Linux: deprecate and warn on legacy --uartX option use
tpwrules Dec 12, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions AntennaTracker/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ class Parameters {
k_param_format_version = 0,
k_param_software_type, // deprecated

k_param_gcs0 = 100, // stream rates for uartA
k_param_gcs1, // stream rates for uartC
k_param_gcs0 = 100, // stream rates for SERIAL0
k_param_gcs1, // stream rates for SERIAL1
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial0_baud, // deprecated
Expand All @@ -60,7 +60,7 @@ class Parameters {
k_param_sitl,
k_param_pidPitch_old, // deprecated
k_param_pidYaw_old, // deprecated
k_param_gcs2, // stream rates for uartD
k_param_gcs2, // stream rates for SERIAL2
k_param_serial2_baud, // deprecated

k_param_yaw_slew_time,
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,14 +159,14 @@ class Parameters {

// 110: Telemetry control
//
k_param_gcs0 = 110, // stream rates for uartA
k_param_gcs1, // stream rates for uartC
k_param_gcs0 = 110, // stream rates for SERIAL0
k_param_gcs1, // stream rates for SERIAL1
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial1_baud_old, // deprecated
k_param_telem_delay,
k_param_serial0_baud_old, // deprecated
k_param_gcs2, // stream rates for uartD
k_param_gcs2, // stream rates for SERIAL2
k_param_serial2_baud_old, // deprecated
k_param_serial2_protocol, // deprecated

Expand Down
6 changes: 3 additions & 3 deletions Rover/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,15 +79,15 @@ class Parameters {

// 110: Telemetry control
//
k_param_gcs0 = 110, // stream rates for uartA
k_param_gcs1, // stream rates for uartC
k_param_gcs0 = 110, // stream rates for SERIAL0
k_param_gcs1, // stream rates for SERIAL1
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial0_baud_old, // unused
k_param_serial1_baud_old, // unused
k_param_telem_delay,
k_param_skip_gyro_cal, // unused
k_param_gcs2, // stream rates for uartD
k_param_gcs2, // stream rates for SERIAL2
k_param_serial2_baud_old, // unused
k_param_serial2_protocol, // deprecated, can be deleted
k_param_serial_manager, // serial manager library
Expand Down
29 changes: 14 additions & 15 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -3052,7 +3052,7 @@ def VisionPosition(self):
"""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()
Expand Down Expand Up @@ -3153,7 +3153,7 @@ def BodyFrameOdom(self):
# 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")
Expand Down Expand Up @@ -3293,7 +3293,7 @@ def InvalidJumpTags(self):

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()
Expand Down Expand Up @@ -7193,7 +7193,7 @@ def ProximitySensors(self):
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()
Expand Down Expand Up @@ -7630,7 +7630,7 @@ def RichenPower(self):
})
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)
Expand Down Expand Up @@ -7697,7 +7697,7 @@ def run_IE24(self, proto_ver):
"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)
Expand Down Expand Up @@ -8182,7 +8182,7 @@ def fly_rangefinder_mavlink(self):
"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()
Expand Down Expand Up @@ -8329,17 +8329,16 @@ def RangeFinderDrivers(self):
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,
Expand Down Expand Up @@ -8380,7 +8379,7 @@ def RangeFinderDriversMaxAlt(self):
"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)
Expand Down Expand Up @@ -9776,7 +9775,7 @@ def FETtecESC(self):
"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()
Expand Down Expand Up @@ -10251,7 +10250,7 @@ def test_rplidar(self, sim_device_name, expected_distances):
"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
])

Expand Down
4 changes: 2 additions & 2 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -3160,7 +3160,7 @@ def TerrainLoiter(self):

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,
Expand Down Expand Up @@ -4214,7 +4214,7 @@ def EFITest(self, efi_type, name, sim_name, check_fuel_flow=True):
})

self.customise_SITL_commandline(
["--uartF=sim:%s" % sim_name,
["--serial5=sim:%s" % sim_name,
],
)
self.wait_ready_to_arm()
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/pysim/util.py
Original file line number Diff line number Diff line change
Expand Up @@ -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")

Expand Down
4 changes: 2 additions & 2 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -6114,14 +6114,14 @@ def DepthFinder(self):
'''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
Expand Down
17 changes: 8 additions & 9 deletions Tools/autotest/sim_vehicle.py
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand All @@ -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,
Expand All @@ -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
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Missed one?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That's the only place that name is referenced in the whole source code. I figured it was unused, so I just removed it.

progress("Preparing sitl_periph_gps")
options = vinfo.options["sitl_periph_gps"]['frames']['gps']
defaults_path = frame_info.get('periph_params_filename', None)
Expand Down Expand Up @@ -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")
Expand Down Expand Up @@ -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"])
Expand Down
24 changes: 12 additions & 12 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -2942,7 +2942,7 @@ def customise_SITL_commandline(self,
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()
Expand Down Expand Up @@ -11939,8 +11939,8 @@ def NMEAOutput(self):
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)
Expand Down Expand Up @@ -12556,7 +12556,7 @@ def FRSkyPassThroughStatustext(self):
})
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)
Expand Down Expand Up @@ -12647,7 +12647,7 @@ def FRSkyPassThroughSensorIDs(self):
})
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)
Expand Down Expand Up @@ -12802,7 +12802,7 @@ def FRSkyMAVlite(self):
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()
Expand Down Expand Up @@ -13077,7 +13077,7 @@ def FRSkySPort(self):
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()
Expand Down Expand Up @@ -13150,7 +13150,7 @@ def FRSkyD(self):
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()
Expand Down Expand Up @@ -13269,7 +13269,7 @@ def LTM(self):
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()
Expand Down Expand Up @@ -13312,7 +13312,7 @@ def DEVO(self):
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()
Expand Down Expand Up @@ -13385,7 +13385,7 @@ def MSP_DJI(self):
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()
Expand Down Expand Up @@ -13413,7 +13413,7 @@ def CRSF(self):
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()
Expand Down
Loading