Skip to content

Commit 020a4d4

Browse files
committed
feat(flightcontroller): Make MAVFTP more robust on F4 processors
1 parent d225757 commit 020a4d4

File tree

2 files changed

+90
-11
lines changed

2 files changed

+90
-11
lines changed

ardupilot_methodic_configurator/backend_flightcontroller.py

Lines changed: 88 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131
from ardupilot_methodic_configurator import _
3232
from ardupilot_methodic_configurator.argparse_check_range import CheckRange
3333
from ardupilot_methodic_configurator.backend_flightcontroller_info import BackendFlightcontrollerInfo
34-
from ardupilot_methodic_configurator.backend_mavftp import MAVFTP
34+
from ardupilot_methodic_configurator.backend_mavftp import MAVFTP, MAVFTPSettings
3535
from ardupilot_methodic_configurator.data_model_par_dict import ParDict
3636

3737
# pylint: disable=too-many-lines
@@ -653,7 +653,30 @@ def _download_params_via_mavlink(
653653
break
654654
return parameters
655655

656-
def _download_params_via_mavftp(
656+
def _create_robust_mavftp_settings(self) -> MAVFTPSettings:
657+
"""
658+
Create robust MAVFTP settings optimized for STM32 F4 controllers under workload.
659+
660+
Returns:
661+
MAVFTPSettings: Configured settings with increased timeouts and reduced burst sizes
662+
663+
"""
664+
return MAVFTPSettings(
665+
[
666+
("debug", int, 0),
667+
("pkt_loss_tx", int, 0),
668+
("pkt_loss_rx", int, 0),
669+
("max_backlog", int, 3), # Reduced backlog for better reliability
670+
("burst_read_size", int, 60), # Smaller burst size for stability
671+
("write_size", int, 60),
672+
("write_qsize", int, 3),
673+
("idle_detection_time", float, 3.7),
674+
("read_retry_time", float, 3.0), # Increased retry time
675+
("retry_time", float, 2.0), # Increased retry time
676+
]
677+
)
678+
679+
def _download_params_via_mavftp( # pylint: disable=too-many-locals
657680
self,
658681
progress_callback: Union[None, Callable[[int, int], None]] = None,
659682
parameter_values_filename: Optional[Path] = None,
@@ -676,21 +699,60 @@ def _download_params_via_mavftp(
676699
"""
677700
if self.master is None:
678701
return {}, ParDict()
679-
mavftp = MAVFTP(self.master, target_system=self.master.target_system, target_component=self.master.target_component)
702+
703+
# Create more robust MAVFTP settings for parameter download
704+
# STM32 F4 controllers under workload need longer timeouts
705+
mavftp_settings = self._create_robust_mavftp_settings()
706+
707+
mavftp = MAVFTP(
708+
self.master,
709+
target_system=self.master.target_system,
710+
target_component=self.master.target_component,
711+
settings=mavftp_settings,
712+
)
680713

681714
def get_params_progress_callback(completion: float) -> None:
682715
if progress_callback is not None and completion is not None:
683716
progress_callback(int(completion * 100), 100)
684717

685718
complete_param_filename = str(parameter_values_filename) if parameter_values_filename else "complete.param"
686719
default_param_filename = str(parameter_defaults_filename) if parameter_defaults_filename else "00_default.param"
687-
mavftp.cmd_getparams([complete_param_filename, default_param_filename], progress_callback=get_params_progress_callback)
688-
ret = mavftp.process_ftp_reply("getparams", timeout=40) # on slow links it might take a long time
689-
pdict: dict[str, float] = {}
690-
defdict: ParDict = ParDict()
720+
721+
# Retry logic for increased robustness with STM32 F4 controllers under workload
722+
max_retries = 3
723+
base_timeout = 15
724+
725+
for attempt in range(max_retries):
726+
try:
727+
mavftp.cmd_getparams(
728+
[complete_param_filename, default_param_filename], progress_callback=get_params_progress_callback
729+
)
730+
# Progressive timeout increase for each retry attempt
731+
timeout = base_timeout * (2**attempt) # 15s, 30s, 60s
732+
logging_info(_("Attempt %d/%d: Requesting parameters with %ds timeout"), attempt + 1, max_retries, timeout)
733+
ret = mavftp.process_ftp_reply("getparams", timeout=timeout)
734+
735+
if ret.error_code == 0:
736+
break # Success, exit retry loop
737+
738+
if attempt < max_retries - 1: # Don't sleep after last attempt
739+
sleep_time = 2**attempt # 1s, 2s, 4s exponential backoff
740+
logging_warning(_("Parameter download attempt %d failed, retrying in %ds..."), attempt + 1, sleep_time)
741+
time_sleep(sleep_time)
742+
else:
743+
logging_error(_("All %d parameter download attempts failed"), max_retries)
744+
745+
except Exception as e: # pylint: disable=broad-exception-caught
746+
logging_error(_("Exception during parameter download attempt %d: %s"), attempt + 1, str(e))
747+
if attempt < max_retries - 1:
748+
sleep_time = 2**attempt
749+
time_sleep(sleep_time)
691750

692751
# add a file sync operation to ensure the file is completely written
693752
time_sleep(0.3)
753+
754+
pdict: dict[str, float] = {}
755+
defdict: ParDict = ParDict()
694756
if ret.error_code == 0:
695757
# load the parameters from the file
696758
par_dict = ParDict.from_file(complete_param_filename)
@@ -1152,14 +1214,23 @@ def upload_file(
11521214
"""Upload a file to the flight controller."""
11531215
if self.master is None:
11541216
return False
1155-
mavftp = MAVFTP(self.master, target_system=self.master.target_system, target_component=self.master.target_component)
1217+
1218+
# Use robust MAVFTP settings for better reliability with STM32 F4 controllers
1219+
mavftp_settings = self._create_robust_mavftp_settings()
1220+
mavftp = MAVFTP(
1221+
self.master,
1222+
target_system=self.master.target_system,
1223+
target_component=self.master.target_component,
1224+
settings=mavftp_settings,
1225+
)
11561226

11571227
def put_progress_callback(completion: float) -> None:
11581228
if progress_callback is not None and completion is not None:
11591229
progress_callback(int(completion * 100), 100)
11601230

11611231
mavftp.cmd_put([local_filename, remote_filename], progress_callback=put_progress_callback)
1162-
ret = mavftp.process_ftp_reply("CreateFile", timeout=10)
1232+
# Increased timeout for better reliability
1233+
ret = mavftp.process_ftp_reply("CreateFile", timeout=20)
11631234
if ret.error_code != 0:
11641235
ret.display_message()
11651236
return ret.error_code == 0
@@ -1177,7 +1248,14 @@ def download_last_flight_log(
11771248
logging_error(error_msg)
11781249
return False
11791250

1180-
mavftp = MAVFTP(self.master, target_system=self.master.target_system, target_component=self.master.target_component)
1251+
# Use robust MAVFTP settings for better reliability with STM32 F4 controllers
1252+
mavftp_settings = self._create_robust_mavftp_settings()
1253+
mavftp = MAVFTP(
1254+
self.master,
1255+
target_system=self.master.target_system,
1256+
target_component=self.master.target_component,
1257+
settings=mavftp_settings,
1258+
)
11811259

11821260
def get_progress_callback(completion: float) -> None:
11831261
if progress_callback is not None and completion is not None:

ardupilot_methodic_configurator/backend_mavftp.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -377,7 +377,8 @@ def __init__(
377377

378378
# Reset the flight controller FTP state-machine
379379
self.__send(FTP_OP(self.seq, self.session, OP_ResetSessions, 0, 0, 0, 0, None))
380-
self.process_ftp_reply("ResetSessions")
380+
# Increased timeout for ResetSessions to be more robust on loaded STM32 F4 controllers
381+
self.process_ftp_reply("ResetSessions", timeout=10)
381382

382383
def cmd_ftp(self, args) -> MAVFTPReturn: # noqa PRL0911, pylint: disable=too-many-return-statements, too-many-branches
383384
"""FTP operations."""

0 commit comments

Comments
 (0)