diff --git a/AntennaTracker/Parameters.h b/AntennaTracker/Parameters.h index 972c36f52505e..e43876f8ded8d 100644 --- a/AntennaTracker/Parameters.h +++ b/AntennaTracker/Parameters.h @@ -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 @@ -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, diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 7210bfe777126..2a9a5ef071986 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -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 diff --git a/Rover/Parameters.h b/Rover/Parameters.h index 035d16f4d0ffb..b4b7b019845cd 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -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 diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 449b09064e06a..991f088098d9c 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -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() @@ -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") @@ -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() @@ -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() @@ -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) @@ -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) @@ -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() @@ -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, @@ -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) @@ -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() @@ -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 ]) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 5c76db5d35d88..9c9add4371646 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -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, @@ -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() diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index beed41e777c75..fb20b0c61a942 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -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") diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index f1eeb76c61801..2f0870b351c16 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -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 diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 065b5265c1c53..5a0ccb5c5ddf3 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -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"]) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index b94581334ae6f..04ce66a804d47 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -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() @@ -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) @@ -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) @@ -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) @@ -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() @@ -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() @@ -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() @@ -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() @@ -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() @@ -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() @@ -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() diff --git a/Tools/completion/zsh/_ap_bin b/Tools/completion/zsh/_ap_bin index cc5b7417f6365..8735278916370 100644 --- a/Tools/completion/zsh/_ap_bin +++ b/Tools/completion/zsh/_ap_bin @@ -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[(deprecated) set device string for SERIAL0]:DEVICE:' \ + '--uartC[(deprecated) set device string for SERIAL1]:DEVICE:' \ + '--uartD[(deprecated) set device string for SERIAL2]:DEVICE:' \ + '--uartB[(deprecated) set device string for SERIAL3]:DEVICE:' \ + '--uartE[(deprecated) set device string for SERIAL4]:DEVICE:' \ + '--uartF[(deprecated) set device string for SERIAL5]:DEVICE:' \ + '--uartG[(deprecated) set device string for SERIAL6]:DEVICE:' \ + '--uartH[(deprecated) set device string for SERIAL7]:DEVICE:' \ + '--uartI[(deprecated) set device string for SERIAL8]:DEVICE:' \ + '--uartJ[(deprecated) 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:' \ diff --git a/Tools/ros2/README.md b/Tools/ros2/README.md index bdd055e3f1329..9832e412f999d 100644 --- a/Tools/ros2/README.md +++ b/Tools/ros2/README.md @@ -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 \ \ diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py index 66a71779fa28f..f1a1a4532ea24 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py @@ -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"), diff --git a/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml b/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml index 02ad121f3a9c9..9fa079957a9f8 100644 --- a/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml +++ b/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml @@ -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 diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index 1af0af6f6001a..bbbe091d9412d 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -189,7 +189,7 @@ Next, follow the associated section for your chosen transport, and finally you c - Run SITL (remember to kill any terminals running ardupilot SITL beforehand) ```console # assuming we are using /dev/pts/1 for Ardupilot SITL - sim_vehicle.py -v ArduPlane -DG --console --enable-dds -A "--uartC=uart:/dev/pts/1" + sim_vehicle.py -v ArduPlane -DG --console --enable-dds -A "--serial1=uart:/dev/pts/1" ``` ## Use ROS 2 CLI diff --git a/libraries/AP_FETtecOneWire/README.md b/libraries/AP_FETtecOneWire/README.md index 482670b0fbf83..7f0d2549f02f4 100644 --- a/libraries/AP_FETtecOneWire/README.md +++ b/libraries/AP_FETtecOneWire/README.md @@ -30,7 +30,7 @@ For purchase, connection and configuration information please see the [ArduPilot - check that the ESCs are periodically sending telemetry data - re-init and configure an ESC(s) if not armed (motors not spinning) when - telemetry communication with the ESC(s) is lost -- adds a serial simulator (--uartF=sim:fetteconewireesc) of FETtec OneWire ESCs +- adds a serial simulator (--serial5=sim:fetteconewireesc) of FETtec OneWire ESCs - adds autotest (using the simulator) to: - simulate telemetry voltage, current, temperature, RPM data using SITL internal variables - test the safety switch functionality diff --git a/libraries/AP_HAL/HAL.cpp b/libraries/AP_HAL/HAL.cpp index a2d1216d2b389..6f796c3ab9c6a 100644 --- a/libraries/AP_HAL/HAL.cpp +++ b/libraries/AP_HAL/HAL.cpp @@ -11,16 +11,3 @@ HAL::FunCallbacks::FunCallbacks(void (*setup_fun)(void), void (*loop_fun)(void)) } } - -// access serial ports using SERIALn numbering -AP_HAL::UARTDriver* AP_HAL::HAL::serial(uint8_t sernum) const -{ - UARTDriver **uart_array = const_cast(&uartA); - // this mapping captures the historical use of uartB as SERIAL3 - const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 }; - static_assert(sizeof(mapping) == num_serial, "num_serial must match mapping"); - if (sernum >= num_serial) { - return nullptr; - } - return uart_array[mapping[sernum]]; -} diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index f8827444204f4..fdaee2c43357b 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -20,16 +20,16 @@ class AP_Param; class AP_HAL::HAL { public: - HAL(AP_HAL::UARTDriver* _uartA, // console - AP_HAL::UARTDriver* _uartB, // 1st GPS - AP_HAL::UARTDriver* _uartC, // telem1 - AP_HAL::UARTDriver* _uartD, // telem2 - AP_HAL::UARTDriver* _uartE, // 2nd GPS - AP_HAL::UARTDriver* _uartF, // extra1 - AP_HAL::UARTDriver* _uartG, // extra2 - AP_HAL::UARTDriver* _uartH, // extra3 - AP_HAL::UARTDriver* _uartI, // extra4 - AP_HAL::UARTDriver* _uartJ, // extra5 + HAL(AP_HAL::UARTDriver* _serial0, // console + AP_HAL::UARTDriver* _serial1, // telem1 + AP_HAL::UARTDriver* _serial2, // telem2 + AP_HAL::UARTDriver* _serial3, // 1st GPS + AP_HAL::UARTDriver* _serial4, // 2nd GPS + AP_HAL::UARTDriver* _serial5, // extra1 + AP_HAL::UARTDriver* _serial6, // extra2 + AP_HAL::UARTDriver* _serial7, // extra3 + AP_HAL::UARTDriver* _serial8, // extra4 + AP_HAL::UARTDriver* _serial9, // extra5 AP_HAL::I2CDeviceManager* _i2c_mgr, AP_HAL::SPIDeviceManager* _spi, AP_HAL::WSPIDeviceManager* _wspi, @@ -53,16 +53,17 @@ class AP_HAL::HAL { AP_HAL::CANIface** _can_ifaces) #endif : - uartA(_uartA), - uartB(_uartB), - uartC(_uartC), - uartD(_uartD), - uartE(_uartE), - uartF(_uartF), - uartG(_uartG), - uartH(_uartH), - uartI(_uartI), - uartJ(_uartJ), + serial_array{ + _serial0, + _serial1, + _serial2, + _serial3, + _serial4, + _serial5, + _serial6, + _serial7, + _serial8, + _serial9}, i2c_mgr(_i2c_mgr), spi(_spi), wspi(_wspi), @@ -112,19 +113,6 @@ class AP_HAL::HAL { virtual void run(int argc, char * const argv[], Callbacks* callbacks) const = 0; -private: - // the uartX ports must be contiguous in ram for the serial() method to work - AP_HAL::UARTDriver* uartA; - AP_HAL::UARTDriver* uartB UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartC UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartD UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartE UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartF UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartG UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartH UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartI UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartJ UNUSED_PRIVATE_MEMBER; - public: AP_HAL::I2CDeviceManager* i2c_mgr; AP_HAL::SPIDeviceManager* spi; @@ -151,6 +139,11 @@ class AP_HAL::HAL { static constexpr uint8_t num_serial = 10; +private: + // UART drivers in SERIALn_ order + AP_HAL::UARTDriver* serial_array[num_serial]; + +public: #if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL AP_HAL::SIMState *simstate; #endif @@ -162,3 +155,12 @@ class AP_HAL::HAL { #endif }; + +// access serial ports using SERIALn numbering +inline AP_HAL::UARTDriver* AP_HAL::HAL::serial(uint8_t sernum) const +{ + if (sernum >= ARRAY_SIZE(serial_array)) { + return nullptr; + } + return serial_array[sernum]; +} diff --git a/libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp b/libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp index 328da1698fac6..7a94258ab14c2 100644 --- a/libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp +++ b/libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp @@ -38,7 +38,7 @@ uint16_t buflen = 0; void setup(void) { - hal.scheduler->delay(1000); //Ensure that the uartA can be initialized + hal.scheduler->delay(1000); //Ensure that hal.serial(n) can be initialized #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX uart = hal.serial(0); // console diff --git a/libraries/AP_HAL/examples/UART_test/UART_test.cpp b/libraries/AP_HAL/examples/UART_test/UART_test.cpp index 1af94cb3bdd91..1dd5d5ed011d8 100644 --- a/libraries/AP_HAL/examples/UART_test/UART_test.cpp +++ b/libraries/AP_HAL/examples/UART_test/UART_test.cpp @@ -30,7 +30,7 @@ void setup(void) start all UARTs at 57600 with default buffer sizes */ - hal.scheduler->delay(1000); //Ensure that the uartA can be initialized + hal.scheduler->delay(1000); //Ensure that hal.serial(n) can be initialized setup_uart(hal.serial(0), "SERIAL0"); // console setup_uart(hal.serial(1), "SERIAL1"); // telemetry 1 diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 46b352e5649f5..65ebdfafdaace 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -45,27 +45,27 @@ #endif #ifndef HAL_NO_UARTDRIVER -static HAL_UARTA_DRIVER; -static HAL_UARTB_DRIVER; -static HAL_UARTC_DRIVER; -static HAL_UARTD_DRIVER; -static HAL_UARTE_DRIVER; -static HAL_UARTF_DRIVER; -static HAL_UARTG_DRIVER; -static HAL_UARTH_DRIVER; -static HAL_UARTI_DRIVER; -static HAL_UARTJ_DRIVER; +static HAL_SERIAL0_DRIVER; +static HAL_SERIAL1_DRIVER; +static HAL_SERIAL2_DRIVER; +static HAL_SERIAL3_DRIVER; +static HAL_SERIAL4_DRIVER; +static HAL_SERIAL5_DRIVER; +static HAL_SERIAL6_DRIVER; +static HAL_SERIAL7_DRIVER; +static HAL_SERIAL8_DRIVER; +static HAL_SERIAL9_DRIVER; #else -static Empty::UARTDriver uartADriver; -static Empty::UARTDriver uartBDriver; -static Empty::UARTDriver uartCDriver; -static Empty::UARTDriver uartDDriver; -static Empty::UARTDriver uartEDriver; -static Empty::UARTDriver uartFDriver; -static Empty::UARTDriver uartGDriver; -static Empty::UARTDriver uartHDriver; -static Empty::UARTDriver uartIDriver; -static Empty::UARTDriver uartJDriver; +static Empty::UARTDriver serial0Driver; +static Empty::UARTDriver serial1Driver; +static Empty::UARTDriver serial2Driver; +static Empty::UARTDriver serial3Driver; +static Empty::UARTDriver serial4Driver; +static Empty::UARTDriver serial5Driver; +static Empty::UARTDriver serial6Driver; +static Empty::UARTDriver serial7Driver; +static Empty::UARTDriver serial8Driver; +static Empty::UARTDriver serial9Driver; #endif #if HAL_USE_I2C == TRUE && defined(HAL_I2C_DEVICE_LIST) @@ -136,16 +136,16 @@ AP_IOMCU iomcu(uart_io); HAL_ChibiOS::HAL_ChibiOS() : AP_HAL::HAL( - &uartADriver, - &uartBDriver, - &uartCDriver, - &uartDDriver, - &uartEDriver, - &uartFDriver, - &uartGDriver, - &uartHDriver, - &uartIDriver, - &uartJDriver, + &serial0Driver, + &serial1Driver, + &serial2Driver, + &serial3Driver, + &serial4Driver, + &serial5Driver, + &serial6Driver, + &serial7Driver, + &serial8Driver, + &serial9Driver, &i2cDeviceManager, &spiDeviceManager, #if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST) @@ -155,7 +155,7 @@ HAL_ChibiOS::HAL_ChibiOS() : #endif &analogIn, &storageDriver, - &uartADriver, + &serial0Driver, &gpioDriver, &rcinDriver, &rcoutDriver, diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 911688f643e15..6593dffe7ee3c 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -52,13 +52,13 @@ using namespace ChibiOS; extern ChibiOS::UARTDriver uart_io; #endif -const UARTDriver::SerialDef UARTDriver::_serial_tab[] = { HAL_UART_DEVICE_LIST }; +const UARTDriver::SerialDef UARTDriver::_serial_tab[] = { HAL_SERIAL_DEVICE_LIST }; // handle for UART handling thread thread_t* volatile UARTDriver::uart_rx_thread_ctx; // table to find UARTDrivers from serial number, used for event handling -UARTDriver *UARTDriver::uart_drivers[UART_MAX_DRIVERS]; +UARTDriver *UARTDriver::serial_drivers[UART_MAX_DRIVERS]; // event used to wake up waiting thread. This event number is for // caller threads @@ -104,8 +104,8 @@ serial_num(_serial_num), sdef(_serial_tab[_serial_num]), _baudrate(57600) { - osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many UART drivers"); - uart_drivers[serial_num] = this; + osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many SERIALn drivers"); + serial_drivers[serial_num] = this; } /* @@ -166,11 +166,11 @@ void UARTDriver::uart_rx_thread(void* arg) hal.scheduler->delay_microseconds(1000); for (uint8_t i=0; i_rx_initialised) { - uart_drivers[i]->_rx_timer_tick(); + if (serial_drivers[i]->_rx_initialised) { + serial_drivers[i]->_rx_timer_tick(); } } } diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.h b/libraries/AP_HAL_ChibiOS/UARTDriver.h index 16cac8f8d0d2e..1a045fa9e7e81 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.h +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.h @@ -25,7 +25,7 @@ #define RX_BOUNCE_BUFSIZE 64U #define TX_BOUNCE_BUFSIZE 64U -// enough for uartA to uartJ, plus IOMCU +// enough for serial0 to serial9, plus IOMCU #define UART_MAX_DRIVERS 11 class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { @@ -148,13 +148,13 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { static thread_t* volatile uart_rx_thread_ctx; // table to find UARTDrivers from serial number, used for event handling - static UARTDriver *uart_drivers[UART_MAX_DRIVERS]; + static UARTDriver *serial_drivers[UART_MAX_DRIVERS]; // thread used for writing and reading thread_t* volatile uart_thread_ctx; char uart_thread_name[6]; - // index into uart_drivers table + // index into serial_drivers table uint8_t serial_num; uint32_t _baudrate; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat index effd49fee7a16..ba2212fa9cb62 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat @@ -27,7 +27,7 @@ define HAL_LED_ON 0 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat index 6d10b336b8f81..7a86058449d0d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat @@ -27,7 +27,7 @@ define HAL_LED_ON 0 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc index 5da67a0bdfd8b..f5219200982ed 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc @@ -34,7 +34,7 @@ PD6 USART2_RX USART2 PD8 USART3_TX USART3 PD9 USART3_RX USART3 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc index cd7ef40d20a07..cb5769d8d514b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc @@ -195,7 +195,7 @@ PE6 SPI4_MOSI SPI4 # means sensors off, then it is pulled HIGH in peripheral_power_enable() PE3 VDD_3V3_SENSORS_EN OUTPUT LOW -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat index c3773bc7b89b8..afc44a107c605 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat @@ -86,20 +86,17 @@ USB_STRING_MANUFACTURER "Hex/ProfiCNC" # order of I2C buses I2C_ORDER I2C2 I2C1 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY - -# the normal usage of this ordering is: +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 # if the board has an IOMCU connected via a UART then this defines the @@ -321,7 +318,7 @@ PE6 SPI4_MOSI SPI4 # timing affecting sensor stability. We pull it high by default PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat index 93d2626c16acf..7b20d22a68795 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat @@ -28,18 +28,17 @@ env OPTIMIZE -O2 # order of I2C buses I2C_ORDER I2C1 I2C2 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7 # UART for IOMCU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat index f0486e5b9ca53..c39441ecb0e56 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat @@ -50,7 +50,7 @@ PD9 USART3_RX USART3 PD11 USART3_CTS USART3 PD12 USART3_RTS USART3 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat index 8bec6df8eea62..720f6b747c570 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat @@ -22,18 +22,17 @@ env OPTIMIZE -O2 # order of I2C buses I2C_ORDER I2C1 I2C2 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 # UART for IOMCU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat index 4c95268d937f2..da84f273b9614 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat @@ -24,18 +24,17 @@ USB_STRING_MANUFACTURER "ArduPilot" # order of I2C buses I2C_ORDER I2C3 I2C2 I2C1 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 # UART for IOMCU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat index a833003a0c44d..7bd549b00aa7e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat @@ -35,7 +35,7 @@ PD6 USART2_RX USART2 PD8 USART3_TX USART3 PD9 USART3_RX USART3 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1-IND/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1-IND/hwdef.dat index 186fec11cecc9..00145bb34e56e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1-IND/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1-IND/hwdef.dat @@ -23,18 +23,17 @@ env OPTIMIZE -O2 # order of I2C buses I2C_ORDER I2C3 I2C2 I2C1 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 # UART for IOMCU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef.dat index 5af9e12d7a18b..781cc6e59ff85 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef.dat @@ -356,7 +356,7 @@ PE1 UART8_TX UART8 # timing affecting sensor stability. We pull it high by default. PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat index 002fbad6143b3..bd90c7351d11c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat @@ -50,7 +50,7 @@ PD6 USART2_RX USART2 PD3 USART2_CTS USART2 PD4 USART2_RTS USART2 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +# UART7 maps to SERIAL5. #PE7 UART7_RX UART7 #PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat index 96f0b2f3117a0..67e3ebf22edd1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat @@ -356,7 +356,7 @@ PE6 SPI4_MOSI SPI4 # timing affecting sensor stability. We pull it high by default. PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat index e3e4d983b95db..7993d2e1fec0e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat @@ -83,20 +83,17 @@ define HAL_I2C_INTERNAL_MASK 0 # order of I2C buses I2C_ORDER I2C1 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY - -# the normal usage of this ordering is: +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 # if the board has an IOMCU connected via a UART then this defines the @@ -315,7 +312,7 @@ PE1 UART8_TX UART8 # timing affecting sensor stability. We pull it high by default PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 6b1275bf00a35..f6e0aed8d7321 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -111,9 +111,6 @@ def __init__(self, bootloader=False, signed_fw=False, outdir=None, hwdef=[], def self.dma_exclude_pattern = [] - # map from uart names to SERIALn numbers - self.uart_serial_num = {} - self.mcu_type = None self.dual_USB_enabled = False @@ -1814,75 +1811,51 @@ def get_extra_bylabel(self, label, name, default=None): return default return p.extra_value(name, type=str, default=default) - def get_UART_ORDER(self): - '''get UART_ORDER from SERIAL_ORDER option''' - if self.get_config('UART_ORDER', required=False, aslist=True) is not None: - self.error('Please convert UART_ORDER to SERIAL_ORDER') - serial_order = self.get_config('SERIAL_ORDER', required=False, aslist=True) - if serial_order is None: - return None - if args.bootloader: - # in bootloader SERIAL_ORDER is treated the same as UART_ORDER - return serial_order - map = [0, 3, 1, 2, 4, 5, 6, 7, 8, 9, 10, 11, 12] - while len(serial_order) < 4: - serial_order += ['EMPTY'] - uart_order = [] - for i in range(len(serial_order)): - uart_order.append(serial_order[map[i]]) - self.uart_serial_num[serial_order[i]] = i - return uart_order - def write_UART_config(self, f): '''write UART config defines''' - uart_list = self.get_UART_ORDER() - if uart_list is None: + serial_list = self.get_config('SERIAL_ORDER', required=False, aslist=True) + if serial_list is None: return + while len(serial_list) < 3: # enough ports for CrashCatcher UART discovery + serial_list += ['EMPTY'] f.write('\n// UART configuration\n') # write out which serial ports we actually have - idx = 0 nports = 0 - serial_order = self.get_config('SERIAL_ORDER', required=False, aslist=True) - for serial in serial_order: + for idx, serial in enumerate(serial_list): if serial == 'EMPTY': f.write('#define HAL_HAVE_SERIAL%u 0\n' % idx) else: f.write('#define HAL_HAVE_SERIAL%u 1\n' % idx) nports = nports + 1 - idx += 1 f.write('#define HAL_NUM_SERIAL_PORTS %u\n' % nports) # write out driver declarations for HAL_ChibOS_Class.cpp - devnames = "ABCDEFGHIJ" sdev = 0 - idx = 0 - for dev in uart_list: + for idx, dev in enumerate(serial_list): if dev == 'EMPTY': - f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' % - (devnames[idx], devnames[idx])) + f.write('#define HAL_SERIAL%s_DRIVER Empty::UARTDriver serial%sDriver\n' % + (idx, idx)) sdev += 1 else: f.write( - '#define HAL_UART%s_DRIVER ChibiOS::UARTDriver uart%sDriver(%u)\n' - % (devnames[idx], devnames[idx], sdev)) + '#define HAL_SERIAL%s_DRIVER ChibiOS::UARTDriver serial%sDriver(%u)\n' + % (idx, idx, sdev)) sdev += 1 - idx += 1 - for idx in range(len(uart_list), len(devnames)): - f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' % - (devnames[idx], devnames[idx])) + for idx in range(len(serial_list), 10): + f.write('#define HAL_SERIAL%s_DRIVER Empty::UARTDriver serial%sDriver\n' % + (idx, idx)) if 'IOMCU_UART' in self.config: if 'io_firmware.bin' not in self.romfs: self.error("Need io_firmware.bin in ROMFS for IOMCU") f.write('#define HAL_WITH_IO_MCU 1\n') - idx = len(uart_list) - f.write('#define HAL_UART_IOMCU_IDX %u\n' % idx) + f.write('#define HAL_UART_IOMCU_IDX %u\n' % len(serial_list)) f.write( '#define HAL_UART_IO_DRIVER ChibiOS::UARTDriver uart_io(HAL_UART_IOMCU_IDX)\n' ) - uart_list.append(self.config['IOMCU_UART'][0]) + serial_list.append(self.config['IOMCU_UART'][0]) f.write('#define HAL_HAVE_SERVO_VOLTAGE 1\n') # make the assumption that IO gurantees servo monitoring # all IOMCU capable boards have SBUS out f.write('#define AP_FEATURE_SBUS_OUT 1\n') @@ -1897,17 +1870,17 @@ def write_UART_config(self, f): crash_uart = None # write config for CrashCatcher UART - if not uart_list[0].startswith('OTG') and not uart_list[0].startswith('EMPTY'): - crash_uart = uart_list[0] - elif not uart_list[2].startswith('OTG') and not uart_list[2].startswith('EMPTY'): - crash_uart = uart_list[2] + if not serial_list[0].startswith('OTG') and not serial_list[0].startswith('EMPTY'): + crash_uart = serial_list[0] + elif not serial_list[2].startswith('OTG') and not serial_list[2].startswith('EMPTY'): + crash_uart = serial_list[2] if crash_uart is not None and self.get_config('FLASH_SIZE_KB', type=int) >= 2048: f.write('#define HAL_CRASH_SERIAL_PORT %s\n' % crash_uart) f.write('#define IRQ_DISABLE_HAL_CRASH_SERIAL_PORT() nvicDisableVector(STM32_%s_NUMBER)\n' % crash_uart) f.write('#define RCC_RESET_HAL_CRASH_SERIAL_PORT() rccReset%s(); rccEnable%s(true)\n' % (crash_uart, crash_uart)) f.write('#define HAL_CRASH_SERIAL_PORT_CLOCK STM32_%sCLK\n' % crash_uart) - for dev in uart_list: + for num, dev in enumerate(serial_list): if dev.startswith('UART'): n = int(dev[4:]) elif dev.startswith('USART'): @@ -1918,7 +1891,7 @@ def write_UART_config(self, f): devlist.append('{}') continue else: - self.error("Invalid element %s in UART_ORDER" % dev) + self.error("Invalid element %s in SERIAL_ORDER" % dev) devlist.append('HAL_%s_CONFIG' % dev) tx_line = self.make_line(dev + '_TX') rx_line = self.make_line(dev + '_RX') @@ -1926,12 +1899,12 @@ def write_UART_config(self, f): cts_line = self.make_line(dev + '_CTS') if rts_line != "0": have_rts_cts = True - f.write('#define HAL_HAVE_RTSCTS_SERIAL%u\n' % self.uart_serial_num[dev]) + f.write('#define HAL_HAVE_RTSCTS_SERIAL%u\n' % num) if dev.startswith('OTG2'): f.write( '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2}\n' % dev) # noqa - OTG2_index = uart_list.index(dev) + OTG2_index = serial_list.index(dev) self.dual_USB_enabled = True elif dev.startswith('OTG'): f.write( @@ -1968,44 +1941,44 @@ def write_UART_config(self, f): #endif ''' % (OTG2_index, OTG2_index)) - f.write('#define HAL_UART_DEVICE_LIST %s\n\n' % ','.join(devlist)) + f.write('#define HAL_SERIAL_DEVICE_LIST %s\n\n' % ','.join(devlist)) if not need_uart_driver and not args.bootloader: f.write(''' #ifndef HAL_USE_SERIAL #define HAL_USE_SERIAL HAL_USE_SERIAL_USB #endif ''') - num_uarts = len(devlist) + num_ports = len(devlist) if 'IOMCU_UART' in self.config: - num_uarts -= 1 - if num_uarts > 10: - self.error("Exceeded max num UARTs of 10 (%u)" % num_uarts) - f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % num_uarts) + num_ports -= 1 + if num_ports > 10: + self.error("Exceeded max num SERIALs of 10 (%u)" % num_ports) + f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % num_ports) def write_UART_config_bootloader(self, f): '''write UART config defines''' - uart_list = self.get_UART_ORDER() - if uart_list is None: + serial_list = self.get_config('SERIAL_ORDER', required=False, aslist=True) + if serial_list is None: return f.write('\n// UART configuration\n') devlist = [] - have_uart = False + have_serial = False OTG2_index = None - for u in uart_list: - if u.startswith('OTG2'): + for s in serial_list: + if s.startswith('OTG2'): devlist.append('(BaseChannel *)&SDU2') - OTG2_index = uart_list.index(u) - elif u.startswith('OTG'): + OTG2_index = serial_list.index(s) + elif s.startswith('OTG'): devlist.append('(BaseChannel *)&SDU1') else: - unum = int(u[-1]) - devlist.append('(BaseChannel *)&SD%u' % unum) - have_uart = True + snum = int(s[-1]) + devlist.append('(BaseChannel *)&SD%u' % snum) + have_serial = True if len(devlist) > 0: f.write('#define BOOTLOADER_DEV_LIST %s\n' % ','.join(devlist)) if OTG2_index is not None: f.write('#define HAL_OTG2_UART_INDEX %d\n' % OTG2_index) - if not have_uart: + if not have_serial: f.write(''' #ifndef HAL_USE_SERIAL #define HAL_USE_SERIAL FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py deleted file mode 100755 index d502d91f6113b..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py +++ /dev/null @@ -1,37 +0,0 @@ -#!/usr/bin/env python -''' -convert UART_ORDER in a hwdef.dat into a SERIAL_ORDER -''' - -import sys, shlex - -def convert_file(fname): - lines = open(fname, 'r').readlines() - for i in range(len(lines)): - if lines[i].startswith('SERIAL_ORDER'): - print("Already has SERIAL_ORDER: %s" % fname) - return - - for i in range(len(lines)): - line = lines[i] - if not line.startswith('UART_ORDER'): - continue - a = shlex.split(line, posix=False) - if a[0] != 'UART_ORDER': - continue - uart_order = a[1:] - if not fname.endswith('-bl.dat'): - while len(uart_order) < 4: - uart_order += ['EMPTY'] - a += ['EMPTY'] - map = [ 0, 2, 3, 1, 4, 5, 6, 7, 8, 9, 10, 11, 12 ] - for j in range(len(uart_order)): - a[j+1] = uart_order[map[j]] - a[0] = 'SERIAL_ORDER' - print("%s new order " % fname, a) - lines[i] = ' '.join(a) + '\n' - open(fname, 'w').write(''.join(lines)) - -files=sys.argv[1:] -for fname in files: - convert_file(fname) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat index 827c5ff959228..d5c1c44015b91 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat @@ -209,7 +209,7 @@ PE1 UART8_TX UART8 # timing affecting sensor stability. We pull it high by default. PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat index 4122e0fa57991..4b128cb02b656 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat @@ -209,7 +209,7 @@ PE1 UART8_TX UART8 # timing affecting sensor stability. We pull it high by default. PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp index 9a175a362f7a1..bedff42e98b7d 100644 --- a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp +++ b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp @@ -30,25 +30,24 @@ #include "Util.h" -static Empty::UARTDriver uartADriver; static ESP32::UARTDriver cons(0); -static ESP32::UARTDriver uartBDriver(1); #ifdef HAL_ESP32_WIFI #if HAL_ESP32_WIFI == 1 -static ESP32::WiFiDriver uartCDriver; //tcp, client should connect to 192.168.4.1 port 5760 +static ESP32::WiFiDriver serial1Driver; //tcp, client should connect to 192.168.4.1 port 5760 #elif HAL_ESP32_WIFI == 2 -static ESP32::WiFiUdpDriver uartCDriver; //udp +static ESP32::WiFiUdpDriver serial1Driver; //udp #endif #else -static Empty::UARTDriver uartCDriver; +static Empty::UARTDriver serial1Driver; #endif -static ESP32::UARTDriver uartDDriver(2); -static Empty::UARTDriver uartEDriver; -static Empty::UARTDriver uartFDriver; -static Empty::UARTDriver uartGDriver; -static Empty::UARTDriver uartHDriver; -static Empty::UARTDriver uartIDriver; -static Empty::UARTDriver uartJDriver; +static ESP32::UARTDriver serial2Driver(2); +static ESP32::UARTDriver serial3Driver(1); +static Empty::UARTDriver serial4Driver; +static Empty::UARTDriver serial5Driver; +static Empty::UARTDriver serial6Driver; +static Empty::UARTDriver serial7Driver; +static Empty::UARTDriver serial8Driver; +static Empty::UARTDriver serial9Driver; static Empty::DSP dspDriver; @@ -73,15 +72,15 @@ extern const AP_HAL::HAL& hal; HAL_ESP32::HAL_ESP32() : AP_HAL::HAL( &cons, //Console/mavlink - &uartBDriver, //GPS 1 - &uartCDriver, //Telem 1 - &uartDDriver, //Telem 2 - &uartEDriver, //GPS 2 - &uartFDriver, //Extra 1 - &uartGDriver, //Extra 2 - &uartHDriver, //Extra 3 - &uartIDriver, //Extra 4 - &uartJDriver, //Extra 5 + &serial1Driver, //Telem 1 + &serial2Driver, //Telem 2 + &serial3Driver, //GPS 1 + &serial4Driver, //GPS 2 + &serial5Driver, //Extra 1 + &serial6Driver, //Extra 2 + &serial7Driver, //Extra 3 + &serial8Driver, //Extra 4 + &serial9Driver, //Extra 5 &i2cDeviceManager, &spiDeviceManager, nullptr, diff --git a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp index 2045e9c2893ee..9d03bcabf7895 100644 --- a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp +++ b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp @@ -9,9 +9,10 @@ using namespace Empty; -static UARTDriver uartADriver; -static UARTDriver uartBDriver; -static UARTDriver uartCDriver; +static UARTDriver serial0Driver; +static UARTDriver serial1Driver; +static UARTDriver serial2Driver; +static UARTDriver serial3Driver; static SPIDeviceManager spiDeviceManager; static AnalogIn analogIn; static Storage storageDriver; @@ -25,20 +26,20 @@ static Flash flashDriver; HAL_Empty::HAL_Empty() : AP_HAL::HAL( - &uartADriver, - &uartBDriver, - &uartCDriver, - nullptr, /* no uartD */ - nullptr, /* no uartE */ - nullptr, /* no uartF */ - nullptr, /* no uartG */ - nullptr, /* no uartH */ - nullptr, /* no uartI */ - nullptr, /* no uartJ */ + &serial0Driver, + &serial1Driver, + &serial2Driver, + &serial3Driver, + nullptr, /* no SERIAL4 */ + nullptr, /* no SERIAL5 */ + nullptr, /* no SERIAL6 */ + nullptr, /* no SERIAL7 */ + nullptr, /* no SERIAL8 */ + nullptr, /* no SERIAL9 */ &spiDeviceManager, &analogIn, &storageDriver, - &uartADriver, + &serial0Driver, &gpioDriver, &rcinDriver, &rcoutDriver, diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index 6618e83bc3240..d89296b6a0fec 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -64,16 +64,17 @@ static UtilRPI utilInstance; static Util utilInstance; #endif -// 9 serial ports on Linux -static UARTDriver uartADriver(true); -static UARTDriver uartCDriver(false); -static UARTDriver uartDDriver(false); -static UARTDriver uartEDriver(false); -static UARTDriver uartFDriver(false); -static UARTDriver uartGDriver(false); -static UARTDriver uartHDriver(false); -static UARTDriver uartIDriver(false); -static UARTDriver uartJDriver(false); +// 10 serial ports on Linux +static UARTDriver serial0Driver(true); +static UARTDriver serial1Driver(false); +static UARTDriver serial2Driver(false); +// serial3Driver declared below depending on board type +static UARTDriver serial4Driver(false); +static UARTDriver serial5Driver(false); +static UARTDriver serial6Driver(false); +static UARTDriver serial7Driver(false); +static UARTDriver serial8Driver(false); +static UARTDriver serial9Driver(false); static I2CDeviceManager i2c_mgr_instance; static SPIDeviceManager spi_mgr_instance; @@ -81,11 +82,24 @@ static SPIDeviceManager spi_mgr_instance; #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH -static SPIUARTDriver uartBDriver; +static SPIUARTDriver serial3Driver; #else -static UARTDriver uartBDriver(false); +static UARTDriver serial3Driver(false); #endif +static UARTDriver* serialDrivers[] = { + &serial0Driver, + &serial1Driver, + &serial2Driver, + &serial3Driver, + &serial4Driver, + &serial5Driver, + &serial6Driver, + &serial7Driver, + &serial8Driver, + &serial9Driver, +}; + #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \ @@ -247,22 +261,22 @@ static CANIface* canDrivers[HAL_NUM_CAN_IFACES]; HAL_Linux::HAL_Linux() : AP_HAL::HAL( - &uartADriver, - &uartBDriver, - &uartCDriver, - &uartDDriver, - &uartEDriver, - &uartFDriver, - &uartGDriver, - &uartHDriver, - &uartIDriver, - &uartJDriver, + &serial0Driver, + &serial1Driver, + &serial2Driver, + &serial3Driver, + &serial4Driver, + &serial5Driver, + &serial6Driver, + &serial7Driver, + &serial8Driver, + &serial9Driver, &i2c_mgr_instance, &spi_mgr_instance, &wspi_mgr_instance, &analogIn, &storageDriver, - &uartADriver, + &serial0Driver, &gpioDriver, &rcinDriver, &rcoutDriver, @@ -281,16 +295,16 @@ HAL_Linux::HAL_Linux() : void _usage(void) { - printf("Usage: --serial0 serial0Path --serial1 serial2Path \n"); + printf("Usage: --serial0 serial0Path --serial1 serial1Path \n"); printf("Examples:\n"); printf("\tserial (0 through 9 available):\n"); printf("\t --serial0 /dev/ttyO4\n"); printf("\t --serial3 /dev/ttyS1\n"); - printf("\tlegacy UART options still work, their mappings are:\n"); + printf("\tlegacy UART options are deprecated, their mappings are:\n"); printf("\t -A/--uartA is SERIAL0\n"); - printf("\t -B/--uartB is SERIAL3\n"); - printf("\t -C/--uartC is SERIAL1\n"); + printf("\t -C/--uartC is SERIAL1\n"); // ordering captures the historical use of uartB as SERIAL3 printf("\t -D/--uartD is SERIAL2\n"); + printf("\t -B/--uartB is SERIAL3\n"); printf("\t -E/--uartE is SERIAL4\n"); printf("\t -F/--uartF is SERIAL5\n"); printf("\t -G/--uartG is SERIAL6\n"); @@ -330,28 +344,41 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const const char *module_path = AP_MODULE_DEFAULT_DIRECTORY; #endif + enum long_options { + CMDLINE_SERIAL0 = 1, // must be in 0-9 order and numbered consecutively + CMDLINE_SERIAL1, + CMDLINE_SERIAL2, + CMDLINE_SERIAL3, + CMDLINE_SERIAL4, + CMDLINE_SERIAL5, + CMDLINE_SERIAL6, + CMDLINE_SERIAL7, + CMDLINE_SERIAL8, + CMDLINE_SERIAL9, + }; + int opt; const struct GetOptLong::option options[] = { {"uartA", true, 0, 'A'}, - {"serial0", true, 0, 'A'}, {"uartB", true, 0, 'B'}, - {"serial3", true, 0, 'B'}, {"uartC", true, 0, 'C'}, - {"serial1", true, 0, 'C'}, {"uartD", true, 0, 'D'}, - {"serial2", true, 0, 'D'}, {"uartE", true, 0, 'E'}, - {"serial4", true, 0, 'E'}, {"uartF", true, 0, 'F'}, - {"serial5", true, 0, 'F'}, {"uartG", true, 0, 'G'}, - {"serial6", true, 0, 'G'}, {"uartH", true, 0, 'H'}, - {"serial7", true, 0, 'H'}, {"uartI", true, 0, 'I'}, - {"serial8", true, 0, 'I'}, {"uartJ", true, 0, 'J'}, - {"serial9", true, 0, 'J'}, + {"serial0", true, 0, CMDLINE_SERIAL0}, + {"serial1", true, 0, CMDLINE_SERIAL1}, + {"serial2", true, 0, CMDLINE_SERIAL2}, + {"serial3", true, 0, CMDLINE_SERIAL3}, + {"serial4", true, 0, CMDLINE_SERIAL4}, + {"serial5", true, 0, CMDLINE_SERIAL5}, + {"serial6", true, 0, CMDLINE_SERIAL6}, + {"serial7", true, 0, CMDLINE_SERIAL7}, + {"serial8", true, 0, CMDLINE_SERIAL8}, + {"serial9", true, 0, CMDLINE_SERIAL9}, {"log-directory", true, 0, 'l'}, {"terrain-directory", true, 0, 't'}, {"storage-directory", true, 0, 's'}, @@ -371,34 +398,36 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const while ((opt = gopt.getoption()) != -1) { switch (opt) { case 'A': - uartADriver.set_device_path(gopt.optarg); - break; case 'B': - uartBDriver.set_device_path(gopt.optarg); - break; case 'C': - uartCDriver.set_device_path(gopt.optarg); - break; case 'D': - uartDDriver.set_device_path(gopt.optarg); - break; case 'E': - uartEDriver.set_device_path(gopt.optarg); - break; case 'F': - uartFDriver.set_device_path(gopt.optarg); - break; case 'G': - uartGDriver.set_device_path(gopt.optarg); - break; case 'H': - uartHDriver.set_device_path(gopt.optarg); - break; case 'I': - uartIDriver.set_device_path(gopt.optarg); + case 'J': { + int uart_idx = opt - 'A'; + // ordering captures the historical use of uartB as SERIAL3 + static const uint8_t mapping[] = { 0, 3, 1, 2, 4, 5, 6, 7, 8, 9 }; + int serial_idx = mapping[uart_idx]; + printf("WARNING: deprecated option --uart%c/-%c will be removed in " + "a future release. Use --serial%d instead.\n", + (char)opt, (char)opt, serial_idx); + serialDrivers[serial_idx]->set_device_path(gopt.optarg); break; - case 'J': - uartJDriver.set_device_path(gopt.optarg); + } + case CMDLINE_SERIAL0: + case CMDLINE_SERIAL1: + case CMDLINE_SERIAL2: + case CMDLINE_SERIAL3: + case CMDLINE_SERIAL4: + case CMDLINE_SERIAL5: + case CMDLINE_SERIAL6: + case CMDLINE_SERIAL7: + case CMDLINE_SERIAL8: + case CMDLINE_SERIAL9: + serialDrivers[opt - CMDLINE_SERIAL0]->set_device_path(gopt.optarg); break; case 'l': utilInstance.set_custom_log_directory(gopt.optarg); diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index bf8bc07351097..0d79624ee6bcf 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -53,16 +53,16 @@ static DSP dspDriver; static Empty::OpticalFlow emptyOpticalFlow; static Empty::Flash emptyFlash; -static UARTDriver sitlUart0Driver(0, &sitlState); -static UARTDriver sitlUart1Driver(1, &sitlState); -static UARTDriver sitlUart2Driver(2, &sitlState); -static UARTDriver sitlUart3Driver(3, &sitlState); -static UARTDriver sitlUart4Driver(4, &sitlState); -static UARTDriver sitlUart5Driver(5, &sitlState); -static UARTDriver sitlUart6Driver(6, &sitlState); -static UARTDriver sitlUart7Driver(7, &sitlState); -static UARTDriver sitlUart8Driver(8, &sitlState); -static UARTDriver sitlUart9Driver(9, &sitlState); +static UARTDriver sitlSerial0Driver(0, &sitlState); +static UARTDriver sitlSerial1Driver(1, &sitlState); +static UARTDriver sitlSerial2Driver(2, &sitlState); +static UARTDriver sitlSerial3Driver(3, &sitlState); +static UARTDriver sitlSerial4Driver(4, &sitlState); +static UARTDriver sitlSerial5Driver(5, &sitlState); +static UARTDriver sitlSerial6Driver(6, &sitlState); +static UARTDriver sitlSerial7Driver(7, &sitlState); +static UARTDriver sitlSerial8Driver(8, &sitlState); +static UARTDriver sitlSerial9Driver(9, &sitlState); static I2CDeviceManager i2c_mgr_instance; @@ -81,22 +81,22 @@ static Empty::WSPIDeviceManager wspi_mgr_instance; HAL_SITL::HAL_SITL() : AP_HAL::HAL( - &sitlUart0Driver, /* uartA */ - &sitlUart1Driver, /* uartB */ - &sitlUart2Driver, /* uartC */ - &sitlUart3Driver, /* uartD */ - &sitlUart4Driver, /* uartE */ - &sitlUart5Driver, /* uartF */ - &sitlUart6Driver, /* uartG */ - &sitlUart7Driver, /* uartH */ - &sitlUart8Driver, /* uartI */ - &sitlUart9Driver, /* uartJ */ + &sitlSerial0Driver, + &sitlSerial1Driver, + &sitlSerial2Driver, + &sitlSerial3Driver, + &sitlSerial4Driver, + &sitlSerial5Driver, + &sitlSerial6Driver, + &sitlSerial7Driver, + &sitlSerial8Driver, + &sitlSerial9Driver, &i2c_mgr_instance, &spi_mgr_instance, /* spi */ &wspi_mgr_instance, &sitlAnalogIn, /* analogin */ &sitlStorage, /* storage */ - &sitlUart0Driver, /* console */ + &sitlSerial0Driver, /* console */ &sitlGPIO, /* gpio */ &sitlRCInput, /* rcinput */ &sitlRCOutput, /* rcoutput */ diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index 27f1b063c86a4..618f26a1aeabd 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -83,11 +83,9 @@ void SITL_State::init(int argc, char * const argv[]) { case CMDLINE_SERIAL6: case CMDLINE_SERIAL7: case CMDLINE_SERIAL8: - case CMDLINE_SERIAL9: { - static const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 }; - _uart_path[mapping[opt - CMDLINE_SERIAL0]] = gopt.optarg; + case CMDLINE_SERIAL9: + _serial_path[opt - CMDLINE_SERIAL0] = gopt.optarg; break; - } case CMDLINE_DEFAULTS: defaults_path = strdup(gopt.optarg); break; diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index b7e21d1491cc9..47bb61ee79639 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -61,11 +61,11 @@ class HALSITL::SITL_State : public SITL_State_Common { } // paths for UART devices - const char *_uart_path[9] { + const char *_serial_path[9] { "none:0", - "GPS1", "none:1", "sim:adsb", + "GPS1", "udpclient:127.0.0.1:15550", // for CAN UART test "none:5", "none:6", diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 8ca5afd4526af..461ff51d600be 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -29,11 +29,11 @@ class HALSITL::SITL_State : public SITL_State_Common { } // paths for UART devices - const char *_uart_path[9] { + const char *_serial_path[9] { "tcp:0:wait", - "GPS1", "tcp:2", "tcp:3", + "GPS1", "GPS2", "tcp:5", "tcp:6", diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index a413c3840c799..1daa760e8526c 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -92,16 +92,16 @@ void SITL_State::_usage(void) "\t--gimbal enable simulated MAVLink gimbal\n" "\t--autotest-dir DIR set directory for additional files\n" "\t--defaults path set path to defaults file\n" - "\t--uartA device set device string for UARTA\n" - "\t--uartB device set device string for UARTB\n" - "\t--uartC device set device string for UARTC\n" - "\t--uartD device set device string for UARTD\n" - "\t--uartE device set device string for UARTE\n" - "\t--uartF device set device string for UARTF\n" - "\t--uartG device set device string for UARTG\n" - "\t--uartH device set device string for UARTH\n" - "\t--uartI device set device string for UARTI\n" - "\t--uartJ device set device string for UARTJ\n" + "\t--uartA device (deprecated) set device string for SERIAL0\n" + "\t--uartC device (deprecated) set device string for SERIAL1\n" // ordering captures the historical use of uartB as SERIAL3 + "\t--uartD device (deprecated) set device string for SERIAL2\n" + "\t--uartB device (deprecated) set device string for SERIAL3\n" + "\t--uartE device (deprecated) set device string for SERIAL4\n" + "\t--uartF device (deprecated) set device string for SERIAL5\n" + "\t--uartG device (deprecated) set device string for SERIAL6\n" + "\t--uartH device (deprecated) set device string for SERIAL7\n" + "\t--uartI device (deprecated) set device string for SERIAL8\n" + "\t--uartJ device (deprecated) set device string for SERIAL9\n" "\t--serial0 device set device string for SERIAL0\n" "\t--serial1 device set device string for SERIAL1\n" "\t--serial2 device set device string for SERIAL2\n" @@ -246,7 +246,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) CMDLINE_FGVIEW, CMDLINE_AUTOTESTDIR, CMDLINE_DEFAULTS, - CMDLINE_UARTA, + CMDLINE_UARTA, // must be in A-J order and numbered consecutively CMDLINE_UARTB, CMDLINE_UARTC, CMDLINE_UARTD, @@ -256,7 +256,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) CMDLINE_UARTH, CMDLINE_UARTI, CMDLINE_UARTJ, - CMDLINE_SERIAL0, + CMDLINE_SERIAL0, // must be in 0-9 order and numbered consecutively CMDLINE_SERIAL1, CMDLINE_SERIAL2, CMDLINE_SERIAL3, @@ -458,9 +458,18 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case CMDLINE_UARTG: case CMDLINE_UARTH: case CMDLINE_UARTI: - case CMDLINE_UARTJ: - _uart_path[opt - CMDLINE_UARTA] = gopt.optarg; + case CMDLINE_UARTJ: { + int uart_idx = opt - CMDLINE_UARTA; + // ordering captures the historical use of uartB as SERIAL3 + static const uint8_t mapping[] = { 0, 3, 1, 2, 4, 5, 6, 7, 8, 9 }; + int serial_idx = mapping[uart_idx]; + char uart_letter = (char)(uart_idx)+'A'; + printf("WARNING: deprecated option --uart%c will be removed in a " + "future release. Use --serial%d instead.\n", + uart_letter, serial_idx); + _serial_path[serial_idx] = gopt.optarg; break; + } case CMDLINE_SERIAL0: case CMDLINE_SERIAL1: case CMDLINE_SERIAL2: @@ -470,11 +479,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case CMDLINE_SERIAL6: case CMDLINE_SERIAL7: case CMDLINE_SERIAL8: - case CMDLINE_SERIAL9: { - static const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 }; - _uart_path[mapping[opt - CMDLINE_SERIAL0]] = gopt.optarg; + case CMDLINE_SERIAL9: + _serial_path[opt - CMDLINE_SERIAL0] = gopt.optarg; break; - } case CMDLINE_RTSCTS: _use_rtscts = true; break; diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 9c90928630dea..900ef64ab6162 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -56,11 +56,11 @@ bool UARTDriver::_console; void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) { - if (_portNumber >= ARRAY_SIZE(_sitlState->_uart_path)) { - AP_HAL::panic("port number out of range; you may need to extend _sitlState->_uart_path"); + if (_portNumber >= ARRAY_SIZE(_sitlState->_serial_path)) { + AP_HAL::panic("port number out of range; you may need to extend _sitlState->_serial_path"); } - const char *path = _sitlState->_uart_path[_portNumber]; + const char *path = _sitlState->_serial_path[_portNumber]; if (baud != 0) { _uart_baudrate = baud; @@ -95,11 +95,11 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) char *args1 = strtok_r(nullptr, ":", &saveptr); char *args2 = strtok_r(nullptr, ":", &saveptr); #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) - if (_portNumber == 2 && AP::sitl()->adsb_plane_count >= 0) { + if (_portNumber == 1 && AP::sitl()->adsb_plane_count >= 0) { // this is ordinarily port 5762. The ADSB simulation assumed // this port, so if enabled we assume we'll be doing ADSB... // add sanity check here that we're doing mavlink on this port? - ::printf("SIM-ADSB connection on port %u\n", _portNumber); + ::printf("SIM-ADSB connection on SERIAL%u\n", _portNumber); _connected = true; _sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr); } else @@ -122,7 +122,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) _uart_start_connection(); } else if (strcmp(devtype, "sim") == 0) { if (!_connected) { - ::printf("SIM connection %s:%s on port %u\n", args1, args2, _portNumber); + ::printf("SIM connection %s:%s on SERIAL%u\n", args1, args2, _portNumber); _connected = true; _sim_serial_device = _sitlState->create_serial_sim(args1, args2); } @@ -334,7 +334,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) exit(1); } - fprintf(stderr, "bind port %u for %u\n", + fprintf(stderr, "bind port %u for SERIAL%u\n", (unsigned)ntohs(_listen_sockaddr.sin_port), (unsigned)_portNumber); @@ -352,7 +352,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) exit(1); } - fprintf(stderr, "Serial port %u on TCP port %u\n", _portNumber, + fprintf(stderr, "SERIAL%u on TCP port %u\n", _portNumber, (unsigned)ntohs(_listen_sockaddr.sin_port)); fflush(stdout); } @@ -630,7 +630,7 @@ void UARTDriver::_check_connection(void) setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); fcntl(_fd, F_SETFD, FD_CLOEXEC); - fprintf(stdout, "New connection on serial port %u\n", _portNumber); + fprintf(stdout, "New connection on SERIAL%u\n", _portNumber); } } } @@ -917,7 +917,7 @@ void UARTDriver::handle_reading_from_device_to_readbuffer() close(_fd); _fd = -1; _connected = false; - fprintf(stdout, "Closed connection on serial port %u\n", _portNumber); + fprintf(stdout, "Closed connection on SERIAL%u\n", _portNumber); fflush(stdout); #if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD) if (_portNumber == 0) { @@ -990,7 +990,7 @@ ssize_t UARTDriver::get_system_outqueue_length() const uint32_t UARTDriver::bw_in_bytes_per_second() const { // if connected, assume at least a 10/100Mbps connection - const uint32_t bitrate = (_connected && _tcp_client_addr != nullptr) ? 10E6 : _uart_baudrate; + const uint32_t bitrate = _connected ? 10E6 : _uart_baudrate; return bitrate/10; // convert bits to bytes minus overhead }; #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index d47378a8054da..cac1dc4e7aa2c 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -89,9 +89,6 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { const char *_uart_path; uint32_t _uart_baudrate; - // IPv4 address of target for uartC - const char *_tcp_client_addr; - void _tcp_start_connection(uint16_t port, bool wait_for_connection); void _uart_start_connection(void); void _check_reconnect(); diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh index 64704f9cc7023..fa67876008e8e 100755 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh @@ -15,12 +15,12 @@ LOC2="-35.36274593,149.16516256,585,353.8" } # setup multicast -#UARTA="tcp:0" -UARTA="mcast:" +#SERIAL0="tcp:0" +SERIAL0="mcast:" PLANE_DEFAULTS="$ROOTDIR/Tools/autotest/models/plane-3d.parm" -(cd ArduPlane/AeroBatics1 && $PLANE --instance 1 --home $LOC1 --model plane-3d --uartA $UARTA --defaults $PLANE_DEFAULTS) & -(cd ArduPlane/AeroBatics2 && $PLANE --instance 2 --home $LOC2 --model plane-3d --uartA $UARTA --defaults $PLANE_DEFAULTS) & +(cd ArduPlane/AeroBatics1 && $PLANE --instance 1 --home $LOC1 --model plane-3d --serial0 $SERIAL0 --defaults $PLANE_DEFAULTS) & +(cd ArduPlane/AeroBatics2 && $PLANE --instance 2 --home $LOC2 --model plane-3d --serial0 $SERIAL0 --defaults $PLANE_DEFAULTS) & wait diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index 801b52a163ae0..386d15dbfbc4e 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -27,8 +27,7 @@ #if HAL_UART_NUM_SERIAL_PORTS >= 4 #define SERIALMANAGER_NUM_PORTS HAL_UART_NUM_SERIAL_PORTS #else -// we need a minimum of 4 to allow for a GPS due to the odd ordering -// of hal.uartB as SERIAL3 +// we want a minimum of 4 as the default GPS port is SERIAL3 #define SERIALMANAGER_NUM_PORTS 4 #endif #else diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index 26a30d068d312..36e0cd3fb0851 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -43,7 +43,7 @@ #include "include/mavlink/v2.0/mavlink_types.h" -/// MAVLink stream used for uartA +/// MAVLink streams used for each telemetry port extern AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS]; extern bool gcs_alternative_active[MAVLINK_COMM_NUM_BUFFERS]; diff --git a/libraries/SITL/SIM_ADSB.cpp b/libraries/SITL/SIM_ADSB.cpp index 784d032902642..2168b922946e0 100644 --- a/libraries/SITL/SIM_ADSB.cpp +++ b/libraries/SITL/SIM_ADSB.cpp @@ -164,7 +164,7 @@ void ADSB::send_report(const class Aircraft &aircraft) { if (AP_HAL::millis() < 10000) { // simulated aircraft don't appear until 10s after startup. This avoids a windows - // threading issue with non-blocking sockets and the initial wait on uartA + // threading issue with non-blocking sockets and the initial wait on SERIAL0 return; } diff --git a/libraries/SITL/SIM_AIS.cpp b/libraries/SITL/SIM_AIS.cpp index 4372cabd5dd4f..6aae9c3717331 100644 --- a/libraries/SITL/SIM_AIS.cpp +++ b/libraries/SITL/SIM_AIS.cpp @@ -14,7 +14,7 @@ */ /* Dump logged AIS data to the serial port - ./Tools/autotest/sim_vehicle.py -v Rover -A --uartF=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0 + ./Tools/autotest/sim_vehicle.py -v Rover -A --serial5=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0 param set SERIAL5_PROTOCOL 40 param set AIS_TYPE 1 diff --git a/libraries/SITL/SIM_AIS.h b/libraries/SITL/SIM_AIS.h index 14bc6c90159f9..395f0f11e5bec 100644 --- a/libraries/SITL/SIM_AIS.h +++ b/libraries/SITL/SIM_AIS.h @@ -14,7 +14,7 @@ */ /* Dump logged AIS data to the serial port - ./Tools/autotest/sim_vehicle.py -v Rover --no-mavproxy -A --uartF=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0 + ./Tools/autotest/sim_vehicle.py -v Rover --no-mavproxy -A --serial5=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0 param set SERIAL5_PROTOCOL 40 param set AIS_TYPE 1 diff --git a/libraries/SITL/SIM_CRSF.h b/libraries/SITL/SIM_CRSF.h index bd02e92dded55..c4fcda7efabf8 100644 --- a/libraries/SITL/SIM_CRSF.h +++ b/libraries/SITL/SIM_CRSF.h @@ -15,7 +15,7 @@ /* Simulated CRSF device -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:crsf --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:crsf --speedup=1 param set SERIAL5_PROTOCOL 23 reboot diff --git a/libraries/SITL/SIM_EFI_Hirth.h b/libraries/SITL/SIM_EFI_Hirth.h index cfc32517e6a76..8ccbb8286a8ad 100644 --- a/libraries/SITL/SIM_EFI_Hirth.h +++ b/libraries/SITL/SIM_EFI_Hirth.h @@ -15,7 +15,7 @@ /* simulate Hirth EFI system -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:hirth --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --serial5=sim:hirth --speedup=1 param set SERIAL5_PROTOCOL 24 param set SIM_EFI_TYPE 6 param set EFI_TYPE 6 diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.h b/libraries/SITL/SIM_EFI_MegaSquirt.h index 813e22e5e65d9..352fbd44589eb 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.h +++ b/libraries/SITL/SIM_EFI_MegaSquirt.h @@ -15,7 +15,7 @@ /* simulate MegaSquirt EFI system -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:megasquirt --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --serial5=sim:megasquirt --speedup=1 param set SERIAL5_PROTOCOL 24 param set SIM_EFI_TYPE 1 param set EFI_TYPE 1 diff --git a/libraries/SITL/SIM_FETtecOneWireESC.h b/libraries/SITL/SIM_FETtecOneWireESC.h index 2d983e3b0e6cc..a434d066987bf 100644 --- a/libraries/SITL/SIM_FETtecOneWireESC.h +++ b/libraries/SITL/SIM_FETtecOneWireESC.h @@ -15,7 +15,7 @@ /* Simulator for the FETtecOneWire ESCs -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:fetteconewireesc --speedup=1 --console +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:fetteconewireesc --speedup=1 --console param set SERIAL5_PROTOCOL 38 param set SERIAL5_BAUD 500000 diff --git a/libraries/SITL/SIM_Frsky_D.h b/libraries/SITL/SIM_Frsky_D.h index 5d5c8fa96a36a..eccd37db325a0 100644 --- a/libraries/SITL/SIM_Frsky_D.h +++ b/libraries/SITL/SIM_Frsky_D.h @@ -15,7 +15,7 @@ /* Simulated Frsky D device -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:frsky-d --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:frsky-d --speedup=1 param set SERIAL5_PROTOCOL 3 reboot diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index 63e4b99441c85..f49ff7643337e 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -18,7 +18,7 @@ Usage example: param set SERIAL5_PROTOCOL 5 - sim_vehicle.py -D --console --map -A --uartB=sim:gps:2 + sim_vehicle.py -D --console --map -A --serial5=sim:gps:2 */ #pragma once diff --git a/libraries/SITL/SIM_Gimbal.cpp b/libraries/SITL/SIM_Gimbal.cpp index a1997dd00fbd1..5aede11b3b40a 100644 --- a/libraries/SITL/SIM_Gimbal.cpp +++ b/libraries/SITL/SIM_Gimbal.cpp @@ -258,7 +258,7 @@ void Gimbal::send_report(void) if (now < 10000) { // don't send gimbal reports until 10s after startup. This // avoids a windows threading issue with non-blocking sockets - // and the initial wait on uartA + // and the initial wait on SERIAL0 return; } if (!mavlink.connected && mav_socket.connect(target_address, target_port)) { diff --git a/libraries/SITL/SIM_IntelligentEnergy24.h b/libraries/SITL/SIM_IntelligentEnergy24.h index 68d8782937f62..794addc7a9b03 100644 --- a/libraries/SITL/SIM_IntelligentEnergy24.h +++ b/libraries/SITL/SIM_IntelligentEnergy24.h @@ -15,7 +15,7 @@ /* Simulator for the IntelligentEnergy 2.4kW FuelCell -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:ie24 --speedup=1 --console +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:ie24 --speedup=1 --console param set SERIAL5_PROTOCOL 30 # Generator param set SERIAL5_BAUD 115200 diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index 81ba8ce34972f..221c6c1abe011 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -602,7 +602,7 @@ void Morse::send_report(void) if (now < 10000) { // don't send lidar reports until 10s after startup. This // avoids a windows threading issue with non-blocking sockets - // and the initial wait on uartA + // and the initial wait on SERIAL0 return; } #endif diff --git a/libraries/SITL/SIM_PS_LightWare_SF45B.h b/libraries/SITL/SIM_PS_LightWare_SF45B.h index 901a6c7988ebc..16fd9955734ef 100644 --- a/libraries/SITL/SIM_PS_LightWare_SF45B.h +++ b/libraries/SITL/SIM_PS_LightWare_SF45B.h @@ -15,7 +15,7 @@ /* Simulator for the LightWare S45B proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,54.15,0 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,54.15,0 param set SERIAL5_PROTOCOL 11 # proximity param set PRX1_TYPE 8 # s45b diff --git a/libraries/SITL/SIM_PS_RPLidar.h b/libraries/SITL/SIM_PS_RPLidar.h index bf2444f5cd517..bb694a7bab31c 100644 --- a/libraries/SITL/SIM_PS_RPLidar.h +++ b/libraries/SITL/SIM_PS_RPLidar.h @@ -17,7 +17,7 @@ /* Simulator for the RPLidarA2 proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,54.15,0 --map +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,54.15,0 --map param set SERIAL5_PROTOCOL 11 param set PRX1_TYPE 5 diff --git a/libraries/SITL/SIM_PS_RPLidarA1.h b/libraries/SITL/SIM_PS_RPLidarA1.h index d374354e6b37a..ca0b625270ea5 100644 --- a/libraries/SITL/SIM_PS_RPLidarA1.h +++ b/libraries/SITL/SIM_PS_RPLidarA1.h @@ -15,7 +15,7 @@ /* Simulator for the RPLidarA2 proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara1 --speedup=1 -l 51.8752066,14.6487840,0,0 --map +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara1 --speedup=1 -l 51.8752066,14.6487840,0,0 --map param set SERIAL5_PROTOCOL 11 param set PRX1_TYPE 5 diff --git a/libraries/SITL/SIM_PS_RPLidarA2.h b/libraries/SITL/SIM_PS_RPLidarA2.h index b5beb50f3cf02..785c2bd6bce33 100644 --- a/libraries/SITL/SIM_PS_RPLidarA2.h +++ b/libraries/SITL/SIM_PS_RPLidarA2.h @@ -15,7 +15,7 @@ /* Simulator for the RPLidarA2 proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,0,0 --map +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,0,0 --map param set SERIAL5_PROTOCOL 11 param set PRX1_TYPE 5 diff --git a/libraries/SITL/SIM_PS_TeraRangerTower.h b/libraries/SITL/SIM_PS_TeraRangerTower.h index f17f491bceb67..71b0798d52a35 100644 --- a/libraries/SITL/SIM_PS_TeraRangerTower.h +++ b/libraries/SITL/SIM_PS_TeraRangerTower.h @@ -15,7 +15,7 @@ /* Simulator for the TeraRangerTower proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:terarangertower --speedup=1 -l 51.8752066,14.6487840,54.15,0 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:terarangertower --speedup=1 -l 51.8752066,14.6487840,54.15,0 param set SERIAL5_PROTOCOL 11 param set PRX1_TYPE 3 # terarangertower diff --git a/libraries/SITL/SIM_RF_BLping.h b/libraries/SITL/SIM_RF_BLping.h index 7c76b31d1fc65..762e5de961199 100644 --- a/libraries/SITL/SIM_RF_BLping.h +++ b/libraries/SITL/SIM_RF_BLping.h @@ -15,7 +15,7 @@ /* Simulator for the BLping rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduSub -A --uartF=sim:blping --speedup=1 -l 33.810313,-118.393867,0,185 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduSub -A --serial5=sim:blping --speedup=1 -l 33.810313,-118.393867,0,185 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 23 diff --git a/libraries/SITL/SIM_RF_Benewake_TF02.h b/libraries/SITL/SIM_RF_Benewake_TF02.h index fac8443f6bf65..3d9604559c5ae 100644 --- a/libraries/SITL/SIM_RF_Benewake_TF02.h +++ b/libraries/SITL/SIM_RF_Benewake_TF02.h @@ -15,7 +15,7 @@ /* Simulator for the Benewake TF02 RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tf02 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tf02 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 19 diff --git a/libraries/SITL/SIM_RF_Benewake_TF03.h b/libraries/SITL/SIM_RF_Benewake_TF03.h index f8d86fdbd59d4..cd01419e3338c 100644 --- a/libraries/SITL/SIM_RF_Benewake_TF03.h +++ b/libraries/SITL/SIM_RF_Benewake_TF03.h @@ -15,7 +15,7 @@ /* Simulator for the Benewake TF03 RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tf03 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tf03 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 27 diff --git a/libraries/SITL/SIM_RF_Benewake_TFmini.h b/libraries/SITL/SIM_RF_Benewake_TFmini.h index b204fb6bf023f..5589b5f303bc1 100644 --- a/libraries/SITL/SIM_RF_Benewake_TFmini.h +++ b/libraries/SITL/SIM_RF_Benewake_TFmini.h @@ -15,7 +15,7 @@ /* Simulator for the TFMini RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tfmini --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tfmini --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 20 diff --git a/libraries/SITL/SIM_RF_GYUS42v2.h b/libraries/SITL/SIM_RF_GYUS42v2.h index 308123dd1813c..7188cd30f9f92 100644 --- a/libraries/SITL/SIM_RF_GYUS42v2.h +++ b/libraries/SITL/SIM_RF_GYUS42v2.h @@ -15,7 +15,7 @@ /* Simulator for the GY-US42-v2 serial rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:gyus42v2 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:gyus42v2 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 31 diff --git a/libraries/SITL/SIM_RF_JRE.h b/libraries/SITL/SIM_RF_JRE.h index d10c77a525890..4dbdbfe2c0ffd 100644 --- a/libraries/SITL/SIM_RF_JRE.h +++ b/libraries/SITL/SIM_RF_JRE.h @@ -15,7 +15,7 @@ /* Simulator for the JAE JRE radio altimiter -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:jre --speedup=1 -L KalaupapaCliffs --map +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:jre --speedup=1 -L KalaupapaCliffs --map param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 38 diff --git a/libraries/SITL/SIM_RF_Lanbao.h b/libraries/SITL/SIM_RF_Lanbao.h index a3bc74e87e05d..d773287a3ed45 100644 --- a/libraries/SITL/SIM_RF_Lanbao.h +++ b/libraries/SITL/SIM_RF_Lanbao.h @@ -15,7 +15,7 @@ /* Simulator for the Lanbao rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lanbao --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lanbao --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 26 diff --git a/libraries/SITL/SIM_RF_LeddarOne.h b/libraries/SITL/SIM_RF_LeddarOne.h index ad54ce3899144..21f74ac8a70ce 100644 --- a/libraries/SITL/SIM_RF_LeddarOne.h +++ b/libraries/SITL/SIM_RF_LeddarOne.h @@ -15,7 +15,7 @@ /* Simulator for the LeddarOne rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:leddarone --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:leddarone --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 12 diff --git a/libraries/SITL/SIM_RF_LightWareSerial.h b/libraries/SITL/SIM_RF_LightWareSerial.h index 4591fa4a5c0ac..686b448bcf238 100644 --- a/libraries/SITL/SIM_RF_LightWareSerial.h +++ b/libraries/SITL/SIM_RF_LightWareSerial.h @@ -15,7 +15,7 @@ /* Simulator for the serial LightWare rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lightwareserial --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lightwareserial --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 8 diff --git a/libraries/SITL/SIM_RF_LightWareSerialBinary.h b/libraries/SITL/SIM_RF_LightWareSerialBinary.h index 992a7b160aaca..0454fb28904f2 100644 --- a/libraries/SITL/SIM_RF_LightWareSerialBinary.h +++ b/libraries/SITL/SIM_RF_LightWareSerialBinary.h @@ -15,7 +15,7 @@ /* Simulator for the serial LightWare rangefinder - binary mode -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lightwareserial-binary --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lightwareserial-binary --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 8 diff --git a/libraries/SITL/SIM_RF_MAVLink.h b/libraries/SITL/SIM_RF_MAVLink.h index 23b04bdaf0ea0..9d901ba75a4e6 100644 --- a/libraries/SITL/SIM_RF_MAVLink.h +++ b/libraries/SITL/SIM_RF_MAVLink.h @@ -15,7 +15,7 @@ /* Simulator for the NMEA serial rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rf_mavlink --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rf_mavlink --speedup=1 param set SERIAL5_PROTOCOL 1 param set RNGFND1_TYPE 10 diff --git a/libraries/SITL/SIM_RF_MaxsonarSerialLV.h b/libraries/SITL/SIM_RF_MaxsonarSerialLV.h index 6397637f33ac4..d23a865f7f8fe 100644 --- a/libraries/SITL/SIM_RF_MaxsonarSerialLV.h +++ b/libraries/SITL/SIM_RF_MaxsonarSerialLV.h @@ -15,7 +15,7 @@ /* Simulator for the MaxsonarSerialLV rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:maxsonarseriallv --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:maxsonarseriallv --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 13 diff --git a/libraries/SITL/SIM_RF_NMEA.h b/libraries/SITL/SIM_RF_NMEA.h index d9dbb8079bc3e..4ba8feaf61244 100644 --- a/libraries/SITL/SIM_RF_NMEA.h +++ b/libraries/SITL/SIM_RF_NMEA.h @@ -15,7 +15,7 @@ /* Simulator for the NMEA serial rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:nmea --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:nmea --speedup=1 param set SERIAL5_PROTOCOL 9 param set SERIAL5_BAUD 9600 diff --git a/libraries/SITL/SIM_RF_RDS02UF.h b/libraries/SITL/SIM_RF_RDS02UF.h index a96bb9b56564d..44a387370db6b 100644 --- a/libraries/SITL/SIM_RF_RDS02UF.h +++ b/libraries/SITL/SIM_RF_RDS02UF.h @@ -15,7 +15,7 @@ /* Simulator for the RDS02UF rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rds02uf --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rds02uf --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 36 diff --git a/libraries/SITL/SIM_RF_TeraRanger_Serial.h b/libraries/SITL/SIM_RF_TeraRanger_Serial.h index 314460699fe08..31544f913826a 100644 --- a/libraries/SITL/SIM_RF_TeraRanger_Serial.h +++ b/libraries/SITL/SIM_RF_TeraRanger_Serial.h @@ -12,7 +12,7 @@ */ /* Simulator for the TeraRanger NEO RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:teraranger_serial --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:teraranger_serial --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 35 graph RANGEFINDER.distance diff --git a/libraries/SITL/SIM_RF_USD1_v0.h b/libraries/SITL/SIM_RF_USD1_v0.h index 866c5a8ea3f29..7a3498adb6431 100644 --- a/libraries/SITL/SIM_RF_USD1_v0.h +++ b/libraries/SITL/SIM_RF_USD1_v0.h @@ -15,7 +15,7 @@ /* Simulator for the USD1 v0 Serial RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:USD1_v0 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:USD1_v0 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 11 diff --git a/libraries/SITL/SIM_RF_USD1_v1.h b/libraries/SITL/SIM_RF_USD1_v1.h index 2b3b4901d1c22..d2982e2cb863b 100644 --- a/libraries/SITL/SIM_RF_USD1_v1.h +++ b/libraries/SITL/SIM_RF_USD1_v1.h @@ -15,7 +15,7 @@ /* Simulator for the USD1 v1 Serial RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:USD1_v1 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:USD1_v1 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 11 diff --git a/libraries/SITL/SIM_RF_Wasp.h b/libraries/SITL/SIM_RF_Wasp.h index e52d9aba989d4..a1e9b37acf5e5 100644 --- a/libraries/SITL/SIM_RF_Wasp.h +++ b/libraries/SITL/SIM_RF_Wasp.h @@ -15,7 +15,7 @@ /* Simulator for the Wasp serial rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:wasp --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:wasp --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 18 diff --git a/libraries/SITL/SIM_RichenPower.h b/libraries/SITL/SIM_RichenPower.h index f0d604c60528e..1fa763fcf2778 100644 --- a/libraries/SITL/SIM_RichenPower.h +++ b/libraries/SITL/SIM_RichenPower.h @@ -15,7 +15,7 @@ /* Simulator for the RichenPower Hybrid generators -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:richenpower --speedup=1 --console +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:richenpower --speedup=1 --console param set SERIAL5_PROTOCOL 30 param set SERIAL5_BAUD 9600 diff --git a/libraries/SITL/SIM_VectorNav.h b/libraries/SITL/SIM_VectorNav.h index 436e19cd22d0b..589539e5d9a8f 100644 --- a/libraries/SITL/SIM_VectorNav.h +++ b/libraries/SITL/SIM_VectorNav.h @@ -20,7 +20,7 @@ AHRS_EKF_TYPE = 11 EAHRS_TYPE=1 - sim_vehicle.py -D --console --map -A --uartF=sim:VectorNav + sim_vehicle.py -D --console --map -A --serial5=sim:VectorNav */ #pragma once diff --git a/libraries/SITL/examples/Airsim/follow-copter.sh b/libraries/SITL/examples/Airsim/follow-copter.sh index 29fe62d0b7b64..47625999c82c9 100755 --- a/libraries/SITL/examples/Airsim/follow-copter.sh +++ b/libraries/SITL/examples/Airsim/follow-copter.sh @@ -46,7 +46,7 @@ BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm,$ROOTDIR/Tools } # start up main copter in the current directory -$COPTER --model airsim-copter --uartA udpclient:$GCS_IP --uartC mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS & +$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP --serial1 mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS & # Set number of extra copters to be simulated, change this for increasing the count NCOPTERS="1" @@ -71,7 +71,7 @@ FOLL_SYSID $FOLL_SYSID FOLL_DIST_MAX 1000 EOF pushd copter$i - $COPTER --model airsim-copter --uartA tcp:0 --uartC mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & + $COPTER --model airsim-copter --serial0 tcp:0 --serial1 mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & popd done wait diff --git a/libraries/SITL/examples/Airsim/multi_vehicle.sh b/libraries/SITL/examples/Airsim/multi_vehicle.sh index 4fdd20301754b..f02717e6fc389 100755 --- a/libraries/SITL/examples/Airsim/multi_vehicle.sh +++ b/libraries/SITL/examples/Airsim/multi_vehicle.sh @@ -28,7 +28,7 @@ BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm,$ROOTDIR/Tools } # start up main copter in the current directory -$COPTER --model airsim-copter --uartA udpclient:$GCS_IP:14550 --uartB tcp:0 --defaults $BASE_DEFAULTS & +$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:14550 --serial3 tcp:0 --defaults $BASE_DEFAULTS & # Set number of "extra" copters to be simulated, change this for increasing the count NCOPTERS="1" @@ -49,7 +49,7 @@ SYSID_THISMAV $SYSID EOF pushd copter$i - $COPTER --model airsim-copter --uartA udpclient:$GCS_IP:$UDP_PORT --uartB tcp:$i \ + $COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:$UDP_PORT --serial3 tcp:$i \ --instance $i --defaults $BASE_DEFAULTS,identity.parm & popd done diff --git a/libraries/SITL/examples/Follow/plane_quad.sh b/libraries/SITL/examples/Follow/plane_quad.sh index 49dd4fd02aa46..171bcdff20cbd 100755 --- a/libraries/SITL/examples/Follow/plane_quad.sh +++ b/libraries/SITL/examples/Follow/plane_quad.sh @@ -13,14 +13,14 @@ PLANE=$ROOTDIR/build/sitl/bin/arduplane } # setup for either TCP or multicast -#UARTA="tcp:0" -UARTA="mcast:" +#SERIAL0="tcp:0" +SERIAL0="mcast:" PLANE_DEFAULTS="$ROOTDIR/Tools/autotest/models/plane.parm" COPTER_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm" mkdir -p swarm/plane swarm/copter -(cd swarm/plane && $PLANE --model plane --uartA $UARTA --defaults $PLANE_DEFAULTS) & +(cd swarm/plane && $PLANE --model plane --serial0 $SERIAL0 --defaults $PLANE_DEFAULTS) & # create default parameter file for the follower cat < swarm/copter/follow.parm @@ -32,5 +32,5 @@ FOLL_SYSID 1 FOLL_DIST_MAX 1000 EOF -(cd swarm/copter && $COPTER --model quad --uartA $UARTA --instance 1 --defaults $COPTER_DEFAULTS,follow.parm) & +(cd swarm/copter && $COPTER --model quad --serial0 $SERIAL0 --instance 1 --defaults $COPTER_DEFAULTS,follow.parm) & wait diff --git a/libraries/SITL/examples/Morse/start_follow.sh b/libraries/SITL/examples/Morse/start_follow.sh index 7e5300fcaa6cc..e213eaeb8daad 100755 --- a/libraries/SITL/examples/Morse/start_follow.sh +++ b/libraries/SITL/examples/Morse/start_follow.sh @@ -9,7 +9,7 @@ GCS_IP=192.168.2.48 BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/rover.parm,$ROOTDIR/Tools/autotest/default_params/rover-skid.parm" # start up main rover in the current directory -$ROVER --model morse-skid --uartA udpclient:$GCS_IP --uartC mcast: --defaults $BASE_DEFAULTS & +$ROVER --model morse-skid --serial0 udpclient:$GCS_IP --serial1 mcast: --defaults $BASE_DEFAULTS & # now start 2 rovers to follow the first, using # a separate directory for each to keep the eeprom.bin @@ -37,7 +37,7 @@ FOLL_SYSID $FOLL_SYSID FOLL_DIST_MAX 1000 EOF pushd rov$i - $ROVER --model "morse-skid:127.0.0.1:$port1:$port2" --uartA tcp:0 --uartC mcast: --instance $i --defaults $BASE_DEFAULTS,follow.parm & + $ROVER --model "morse-skid:127.0.0.1:$port1:$port2" --serial0 tcp:0 --serial1 mcast: --instance $i --defaults $BASE_DEFAULTS,follow.parm & popd done wait diff --git a/libraries/SITL/examples/follow-copter.sh b/libraries/SITL/examples/follow-copter.sh index 8806700171952..8dbeebc75f0d6 100755 --- a/libraries/SITL/examples/follow-copter.sh +++ b/libraries/SITL/examples/follow-copter.sh @@ -75,7 +75,7 @@ AUTO_OPTIONS 7 EOF pushd copter1 -$COPTER --model quad --home=$HOMELAT,$HOMELONG,$HOMEALT,0 --uartA udpclient:$GCS_IP --uartC mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS,leader.parm & +$COPTER --model quad --home=$HOMELAT,$HOMELONG,$HOMEALT,0 --serial0 udpclient:$GCS_IP --serial1 mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS,leader.parm & popd # now start other copters to follow the first, using @@ -103,7 +103,7 @@ EOF pushd copter$i LAT=$(echo "$HOMELAT + 0.0005*$i" | bc -l) LONG=$(echo "$HOMELONG + 0.0005*$i" | bc -l) - $COPTER --model quad --home=$LAT,$LONG,$HOMEALT,0 --uartA tcp:0 --uartC mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & + $COPTER --model quad --home=$LAT,$LONG,$HOMEALT,0 --serial0 tcp:0 --serial1 mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & popd done wait