13
13
from logging import warning as logging_warning
14
14
from logging import error as logging_error
15
15
16
- # import sys
16
+ from sys import exit as sys_exit
17
17
from time import sleep as time_sleep
18
18
from os import path as os_path
19
19
from os import name as os_name
20
20
from os import readlink as os_readlink
21
21
from typing import Dict
22
+ from typing import Tuple
22
23
23
24
import serial .tools .list_ports
24
25
import serial .tools .list_ports_common
28
29
from MethodicConfigurator .annotate_params import Par
29
30
30
31
from MethodicConfigurator .backend_flightcontroller_info import BackendFlightcontrollerInfo
32
+ from MethodicConfigurator .backend_mavftp import MAVFTP
33
+ from MethodicConfigurator .param_ftp import ftp_param_decode
31
34
32
35
from MethodicConfigurator .argparse_check_range import CheckRange
33
36
@@ -268,12 +271,13 @@ def __process_autopilot_version(self, m):
268
271
self .info .set_vendor_id_and_product_id (m .vendor_id , m .product_id )
269
272
return ""
270
273
271
- def download_params (self , progress_callback = None ) -> Dict [str , float ]:
274
+ def download_params (self , progress_callback = None ) -> Tuple [ Dict [str , float ], Dict [ str , float ] ]:
272
275
"""
273
276
Requests all flight controller parameters from a MAVLink connection.
274
277
275
278
Returns:
276
279
Dict[str, float]: A dictionary of flight controller parameters.
280
+ Dict[str, float]: A dictionary of flight controller default parameters.
277
281
"""
278
282
# FIXME this entire if statement is for testing only, remove it later pylint: disable=fixme
279
283
if self .master is None and self .comport is not None and self .comport .device == 'test' :
@@ -287,17 +291,13 @@ def download_params(self, progress_callback=None) -> Dict[str, float]:
287
291
288
292
# Check if MAVFTP is supported
289
293
if self .info .is_mavftp_supported :
290
- logging_info ("MAVFTP is supported by the %s flight controller, but not yet from this SW " ,
294
+ logging_info ("MAVFTP is supported by the %s flight controller" ,
291
295
self .comport .device )
292
296
293
- # FIXME remove this call and uncomment below once it works pylint: disable=fixme
294
- return self .__download_params_via_mavlink (progress_callback )
295
-
296
- # parameters, _defaults = self.download_params_via_mavftp(progress_callback)
297
- # return parameters
297
+ return self .download_params_via_mavftp (progress_callback )
298
298
299
299
logging_info ("MAVFTP is not supported by the %s flight controller, fallback to MAVLink" , self .comport .device )
300
- return self .__download_params_via_mavlink (progress_callback )
300
+ return self .__download_params_via_mavlink (progress_callback ), {}
301
301
302
302
def __download_params_via_mavlink (self , progress_callback = None ) -> Dict [str , float ]:
303
303
logging_debug ("Will fetch all parameters from the %s flight controller" , self .comport .device )
@@ -332,6 +332,51 @@ def __download_params_via_mavlink(self, progress_callback=None) -> Dict[str, flo
332
332
break
333
333
return parameters
334
334
335
+ def download_params_via_mavftp (self , progress_callback = None ) -> Tuple [Dict [str , float ], Dict [str , float ]]:
336
+ # FIXME global variables should be avoided but I found no other practical way get the FTP result pylint: disable=fixme
337
+ global ftp_should_run # pylint: disable=global-variable-undefined
338
+ global pdict # pylint: disable=global-variable-undefined
339
+ global defdict # pylint: disable=global-variable-undefined
340
+ ftp_should_run = True
341
+ pdict = {}
342
+ defdict = {}
343
+
344
+ mavftp = MAVFTP (self .master ,
345
+ target_system = self .master .target_system ,
346
+ target_component = self .master .target_component )
347
+
348
+ def callback (fh ):
349
+ '''called on ftp completion'''
350
+ global ftp_should_run # pylint: disable=global-variable-undefined
351
+ global pdict # pylint: disable=global-variable-not-assigned
352
+ global defdict # pylint: disable=global-variable-not-assigned
353
+ data = fh .read ()
354
+ logging_info ("'MAVFTP get' parameter values and defaults done, got %u bytes" , len (data ))
355
+ pdata = ftp_param_decode (data )
356
+ if pdata is None :
357
+ logging_error ("param decode failed" )
358
+ sys_exit (1 )
359
+
360
+ for (name , value , _ptype ) in pdata .params :
361
+ pdict [name .decode ('utf-8' )] = value
362
+ logging_info ("got %u parameter values" , len (pdict ))
363
+ if pdata .defaults :
364
+ for (name , value , _ptype ) in pdata .defaults :
365
+ defdict [name .decode ('utf-8' )] = value
366
+ logging_info ("got %u parameter default values" , len (defdict ))
367
+ ftp_should_run = False
368
+ progress_callback (len (data ), len (data ))
369
+
370
+ mavftp .cmd_get (['@PARAM/param.pck?withdefaults=1' ], callback = callback , callback_progress = progress_callback )
371
+
372
+ while ftp_should_run :
373
+ m = self .master .recv_match (type = ['FILE_TRANSFER_PROTOCOL' ], timeout = 0.1 )
374
+ if m is not None :
375
+ mavftp .mavlink_packet (m )
376
+ mavftp .idle_task ()
377
+
378
+ return pdict , defdict
379
+
335
380
def set_param (self , param_name : str , param_value : float ):
336
381
"""
337
382
Set a parameter on the flight controller.
0 commit comments