Skip to content

Commit 5f43c2f

Browse files
committed
FEATURE: Use MAVFTP to speed up download of parameters values
Also downloads and updates parameter default values
1 parent 09a32ea commit 5f43c2f

7 files changed

+200
-211
lines changed

MethodicConfigurator/annotate_params.py

Lines changed: 21 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -198,7 +198,7 @@ def missionplanner_sort(item: str) -> Tuple[str, ...]:
198198
return tuple(parts)
199199

200200
@staticmethod
201-
def format_params(param_dict: Dict[str, 'Par'], file_format: str = "missionplanner") -> List[str]:
201+
def format_params(param_dict: Dict[str, 'Par'], file_format: str = "missionplanner") -> List[str]: # pylint: disable=too-many-branches
202202
"""
203203
Formats the parameters in the provided dictionary into a list of strings.
204204
@@ -225,17 +225,23 @@ def format_params(param_dict: Dict[str, 'Par'], file_format: str = "missionplann
225225
formatted_params = []
226226
if file_format == "missionplanner":
227227
for key, parameter in param_dict.items():
228-
if parameter.comment:
229-
formatted_params.append(f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')}"
230-
f" # {parameter.comment}")
228+
if isinstance(parameter, dict):
229+
if parameter.comment:
230+
formatted_params.append(f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')}"
231+
f" # {parameter.comment}")
232+
else:
233+
formatted_params.append(f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')}")
231234
else:
232-
formatted_params.append(f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')}")
235+
formatted_params.append(f"{key},{format(parameter, '.6f').rstrip('0').rstrip('.')}")
233236
elif file_format == "mavproxy":
234237
for key, parameter in param_dict.items():
235-
if parameter.comment:
236-
formatted_params.append(f"{key:<16} {parameter.value:<8.6f} # {parameter.comment}")
238+
if isinstance(parameter, dict):
239+
if parameter.comment:
240+
formatted_params.append(f"{key:<16} {parameter.value:<8.6f} # {parameter.comment}")
241+
else:
242+
formatted_params.append(f"{key:<16} {parameter.value:<8.6f}")
237243
else:
238-
formatted_params.append(f"{key:<16} {parameter.value:<8.6f}")
244+
formatted_params.append(f"{key:<16} {parameter:<8.6f}")
239245
return formatted_params
240246

241247
@staticmethod
@@ -690,9 +696,7 @@ def get_xml_url(vehicle_type: str, firmware_version: str) -> str:
690696
def parse_parameter_metadata(xml_url: str, xml_dir: str, xml_file: str,
691697
vehicle_type: str, max_line_length: int) -> Dict[str, Any]:
692698
xml_root = get_xml_data(xml_url, xml_dir, xml_file)
693-
param_default_dict = load_default_param_file(xml_dir)
694-
doc_dict = create_doc_dict(xml_root, vehicle_type, max_line_length)
695-
return doc_dict, param_default_dict
699+
return create_doc_dict(xml_root, vehicle_type, max_line_length)
696700

697701

698702
def main():
@@ -701,8 +705,9 @@ def main():
701705
xml_url = get_xml_url(args.vehicle_type, args.firmware_version)
702706
xml_dir = get_xml_dir(args.target)
703707

704-
[doc_dict, param_default_dict] = parse_parameter_metadata(xml_url, xml_dir, PARAM_DEFINITION_XML_FILE,
705-
args.vehicle_type, args.max_line_length)
708+
doc_dict = parse_parameter_metadata(xml_url, xml_dir, PARAM_DEFINITION_XML_FILE,
709+
args.vehicle_type, args.max_line_length)
710+
param_default_dict = load_default_param_file(xml_dir)
706711
update_parameter_documentation(doc_dict, args.target, args.sort, param_default_dict,
707712
args.delete_documentation_annotations)
708713
if args.verbose:
@@ -711,9 +716,10 @@ def main():
711716
# Annotate lua MAGfit XML documentation into the respective parameter file
712717
xml_file = LUA_PARAM_DEFINITION_XML_FILE
713718
if os_path.isfile(os_path.join(os_path.dirname(args.target), xml_file)):
714-
[doc_dict, param_default_dict] = parse_parameter_metadata(xml_url, xml_dir, xml_file,
715-
args.vehicle_type, args.max_line_length)
719+
doc_dict = parse_parameter_metadata(xml_url, xml_dir, xml_file,
720+
args.vehicle_type, args.max_line_length)
716721
target = os_path.join(os_path.dirname(args.target), "24_inflight_magnetometer_fit_setup.param")
722+
param_default_dict = load_default_param_file(xml_dir)
717723
update_parameter_documentation(doc_dict, target, args.sort, param_default_dict,
718724
args.delete_documentation_annotations)
719725
else:

MethodicConfigurator/ardupilot_methodic_configurator.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -116,8 +116,10 @@ def main():
116116
# Connect to the flight controller and read the parameters
117117
flight_controller, vehicle_type = connect_to_fc_and_read_parameters(args)
118118

119+
param_default_values = {}
119120
if flight_controller.master is not None or args.device == 'test':
120-
FlightControllerInfoWindow(flight_controller)
121+
fciw = FlightControllerInfoWindow(flight_controller)
122+
param_default_values = fciw.get_param_default_values()
121123

122124
try:
123125
local_filesystem = LocalFilesystem(args.vehicle_dir, vehicle_type, flight_controller.info.flight_sw_version,
@@ -126,6 +128,9 @@ def main():
126128
show_error_message("Fatal error reading parameter files", f"{exp}")
127129
raise
128130

131+
if param_default_values:
132+
local_filesystem.write_param_default_values(param_default_values)
133+
129134
# Get the list of intermediate parameter files files that will be processed sequentially
130135
files = list(local_filesystem.file_parameters.keys()) if local_filesystem.file_parameters else []
131136

MethodicConfigurator/backend_filesystem.py

Lines changed: 18 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
from MethodicConfigurator.annotate_params import PARAM_DEFINITION_XML_FILE, Par
3434
from MethodicConfigurator.annotate_params import get_xml_url
3535
from MethodicConfigurator.annotate_params import get_xml_dir
36+
from MethodicConfigurator.annotate_params import load_default_param_file
3637
from MethodicConfigurator.annotate_params import parse_parameter_metadata
3738
from MethodicConfigurator.annotate_params import format_columns
3839
from MethodicConfigurator.annotate_params import split_into_lines
@@ -88,12 +89,12 @@ def __init__(self, vehicle_dir: str, vehicle_type: str, fw_version: str, allow_e
8889
self.vehicle_type = vehicle_type
8990
self.fw_version = fw_version
9091
self.allow_editing_template_files = allow_editing_template_files
92+
self.param_default_dict = {}
9193
if vehicle_dir is not None:
9294
self.re_init(vehicle_dir, vehicle_type)
9395

9496
def re_init(self, vehicle_dir: str, vehicle_type: str):
9597
self.vehicle_dir = vehicle_dir
96-
self.param_default_dict = {}
9798
self.doc_dict = {}
9899

99100
if not self.load_vehicle_components_json_data(vehicle_dir):
@@ -122,15 +123,16 @@ def re_init(self, vehicle_dir: str, vehicle_type: str):
122123
# Read ArduPilot parameter documentation
123124
xml_url = get_xml_url(vehicle_type, self.fw_version)
124125
xml_dir = get_xml_dir(vehicle_dir)
125-
[self.doc_dict, self.param_default_dict] = parse_parameter_metadata(xml_url, xml_dir, PARAM_DEFINITION_XML_FILE,
126-
vehicle_type, TOOLTIP_MAX_LENGTH)
126+
self.doc_dict = parse_parameter_metadata(xml_url, xml_dir, PARAM_DEFINITION_XML_FILE,
127+
vehicle_type, TOOLTIP_MAX_LENGTH)
128+
self.param_default_dict = load_default_param_file(xml_dir)
127129

128130
# Extend parameter documentation metadata if <parameter_file>.pdef.xml exists
129131
for filename in self.file_parameters:
130132
pdef_xml_file = filename.replace(".param", ".pdef.xml")
131133
if os_path.exists(os_path.join(xml_dir, pdef_xml_file)):
132-
[doc_dict, _param_default_dict] = parse_parameter_metadata("", xml_dir, pdef_xml_file,
133-
vehicle_type, TOOLTIP_MAX_LENGTH)
134+
doc_dict = parse_parameter_metadata("", xml_dir, pdef_xml_file,
135+
vehicle_type, TOOLTIP_MAX_LENGTH)
134136
self.doc_dict.update(doc_dict)
135137

136138
self.__extend_and_reformat_parameter_documentation_metadata()
@@ -530,6 +532,17 @@ def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters:
530532
Par.export_to_param(Par.format_params(param_dict), os_path.join(self.vehicle_dir, param_filename))
531533
return ''
532534

535+
def write_param_default_values(self, param_default_values: Dict[str, float]):
536+
param_default_values = dict(sorted(param_default_values.items()))
537+
if self.param_default_dict != param_default_values:
538+
self.param_default_dict = param_default_values
539+
return True
540+
return False
541+
542+
def write_param_default_values_to_file(self, param_default_values: Dict[str, float], filename: str='00_default.param'):
543+
if self.write_param_default_values(param_default_values):
544+
Par.export_to_param(Par.format_params(param_default_values), os_path.join(self.vehicle_dir, filename))
545+
533546
@staticmethod
534547
def add_argparse_arguments(parser):
535548
parser.add_argument('-t', '--vehicle-type',

MethodicConfigurator/backend_flightcontroller.py

Lines changed: 54 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -13,12 +13,13 @@
1313
from logging import warning as logging_warning
1414
from logging import error as logging_error
1515

16-
# import sys
16+
from sys import exit as sys_exit
1717
from time import sleep as time_sleep
1818
from os import path as os_path
1919
from os import name as os_name
2020
from os import readlink as os_readlink
2121
from typing import Dict
22+
from typing import Tuple
2223

2324
import serial.tools.list_ports
2425
import serial.tools.list_ports_common
@@ -28,6 +29,8 @@
2829
from MethodicConfigurator.annotate_params import Par
2930

3031
from MethodicConfigurator.backend_flightcontroller_info import BackendFlightcontrollerInfo
32+
from MethodicConfigurator.backend_mavftp import MAVFTP
33+
from MethodicConfigurator.param_ftp import ftp_param_decode
3134

3235
from MethodicConfigurator.argparse_check_range import CheckRange
3336

@@ -268,12 +271,13 @@ def __process_autopilot_version(self, m):
268271
self.info.set_vendor_id_and_product_id(m.vendor_id, m.product_id)
269272
return ""
270273

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]]:
272275
"""
273276
Requests all flight controller parameters from a MAVLink connection.
274277
275278
Returns:
276279
Dict[str, float]: A dictionary of flight controller parameters.
280+
Dict[str, float]: A dictionary of flight controller default parameters.
277281
"""
278282
# FIXME this entire if statement is for testing only, remove it later pylint: disable=fixme
279283
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]:
287291

288292
# Check if MAVFTP is supported
289293
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",
291295
self.comport.device)
292296

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)
298298

299299
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), {}
301301

302302
def __download_params_via_mavlink(self, progress_callback=None) -> Dict[str, float]:
303303
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
332332
break
333333
return parameters
334334

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+
335380
def set_param(self, param_name: str, param_value: float):
336381
"""
337382
Set a parameter on the flight controller.

0 commit comments

Comments
 (0)