@@ -271,13 +271,13 @@ def __process_autopilot_version(self, m):
271
271
self .info .set_vendor_id_and_product_id (m .vendor_id , m .product_id )
272
272
return ""
273
273
274
- def download_params (self , progress_callback = None ) -> Tuple [Dict [str , float ], Dict [str , float ]]:
274
+ def download_params (self , progress_callback = None ) -> Tuple [Dict [str , float ], Dict [str , 'Par' ]]:
275
275
"""
276
276
Requests all flight controller parameters from a MAVLink connection.
277
277
278
278
Returns:
279
279
Dict[str, float]: A dictionary of flight controller parameters.
280
- Dict[str, float ]: A dictionary of flight controller default parameters.
280
+ Dict[str, Par ]: A dictionary of flight controller default parameters.
281
281
"""
282
282
# FIXME this entire if statement is for testing only, remove it later pylint: disable=fixme
283
283
if self .master is None and self .comport is not None and self .comport .device == 'test' :
@@ -332,7 +332,7 @@ 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 ]]:
335
+ def download_params_via_mavftp (self , progress_callback = None ) -> Tuple [Dict [str , float ], Dict [str , 'Par' ]]:
336
336
# FIXME global variables should be avoided but I found no other practical way get the FTP result pylint: disable=fixme
337
337
global ftp_should_run # pylint: disable=global-variable-undefined
338
338
global pdict # pylint: disable=global-variable-undefined
@@ -362,7 +362,7 @@ def callback(fh):
362
362
logging_info ("got %u parameter values" , len (pdict ))
363
363
if pdata .defaults :
364
364
for (name , value , _ptype ) in pdata .defaults :
365
- defdict [name .decode ('utf-8' )] = value
365
+ defdict [name .decode ('utf-8' )] = Par ( value )
366
366
logging_info ("got %u parameter default values" , len (defdict ))
367
367
ftp_should_run = False
368
368
progress_callback (len (data ), len (data ))
0 commit comments