@@ -192,8 +192,10 @@ def get_serials(self) -> List[Serial]:
192
192
logger .error (e )
193
193
return serials
194
194
195
- def get_serial_cmdline (self ) -> str :
196
- return " " .join ([f"-{ entry .port } { entry .endpoint } " for entry in self .get_serials ()])
195
+ def get_serial_cmdline (self , supports_new_serial_mapping : bool ) -> str :
196
+ if supports_new_serial_mapping :
197
+ return " " .join ([f"--serial{ entry .port } { entry .endpoint } " for entry in self .get_serials ()])
198
+ return " " .join ([f"-{ entry .port_as_letter } { entry .endpoint } " for entry in self .get_serials ()])
197
199
198
200
def get_default_params_cmdline (self , platform : Platform ) -> str :
199
201
# check if file exists and return it's path as --defaults parameter
@@ -202,6 +204,17 @@ def get_default_params_cmdline(self, platform: Platform) -> str:
202
204
return f"--defaults { default_params_path } "
203
205
return ""
204
206
207
+ def check_supports_new_serial_mapping (self , firmware : pathlib .Path ) -> bool :
208
+ """
209
+ check if the firmware supports --serialN instead of --uartX by checking the output of --help
210
+ """
211
+ try :
212
+ output = subprocess .check_output ([firmware , "--help" ], encoding = "utf-8" )
213
+ return "--serial" in output
214
+ except Exception as e :
215
+ logger .warning (f"Failed to check if firmware supports new serial mapping: { e } " )
216
+ return False
217
+
205
218
async def start_linux_board (self , board : LinuxFlightController ) -> None :
206
219
self ._current_board = board
207
220
if not self .firmware_manager .is_firmware_installed (self ._current_board ):
@@ -248,12 +261,20 @@ async def start_linux_board(self, board: LinuxFlightController) -> None:
248
261
#
249
262
# The first column comes from https://ardupilot.org/dev/docs/sitl-serial-mapping.html
250
263
264
+ supports_new_serial_mapping = self .check_supports_new_serial_mapping (firmware_path )
265
+
266
+ master_endpoint_str = (
267
+ f" --serial0 udp:{ master_endpoint .place } :{ master_endpoint .argument } "
268
+ if supports_new_serial_mapping
269
+ else f" -A udp:{ master_endpoint .place } :{ master_endpoint .argument } "
270
+ )
271
+
251
272
command_line = (
252
273
f"{ firmware_path } "
253
- f" -A udp: { master_endpoint . place } : { master_endpoint . argument } "
274
+ f"{ master_endpoint_str } "
254
275
f" --log-directory { self .settings .firmware_folder } /logs/"
255
276
f" --storage-directory { self .settings .firmware_folder } /storage/"
256
- f" { self .get_serial_cmdline ()} "
277
+ f" { self .get_serial_cmdline (supports_new_serial_mapping )} "
257
278
f" { self .get_default_params_cmdline (board .platform )} "
258
279
)
259
280
0 commit comments