3131from ardupilot_methodic_configurator import _
3232from ardupilot_methodic_configurator .argparse_check_range import CheckRange
3333from 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
3535from ardupilot_methodic_configurator .data_model_par_dict import ParDict
3636
3737# pylint: disable=too-many-lines
@@ -657,7 +657,30 @@ def _download_params_via_mavlink(
657657 break
658658 return parameters
659659
660- def _download_params_via_mavftp (
660+ def _create_robust_mavftp_settings (self ) -> MAVFTPSettings :
661+ """
662+ Create robust MAVFTP settings optimized for STM32 F4 controllers under workload.
663+
664+ Returns:
665+ MAVFTPSettings: Configured settings with increased timeouts and reduced burst sizes
666+
667+ """
668+ return MAVFTPSettings (
669+ [
670+ ("debug" , int , 0 ),
671+ ("pkt_loss_tx" , int , 0 ),
672+ ("pkt_loss_rx" , int , 0 ),
673+ ("max_backlog" , int , 3 ), # Reduced backlog for better reliability
674+ ("burst_read_size" , int , 60 ), # Smaller burst size for stability
675+ ("write_size" , int , 60 ),
676+ ("write_qsize" , int , 3 ),
677+ ("idle_detection_time" , float , 3.7 ),
678+ ("read_retry_time" , float , 3.0 ), # Increased retry time
679+ ("retry_time" , float , 2.0 ), # Increased retry time
680+ ]
681+ )
682+
683+ def _download_params_via_mavftp ( # pylint: disable=too-many-locals
661684 self ,
662685 progress_callback : Union [None , Callable [[int , int ], None ]] = None ,
663686 parameter_values_filename : Optional [Path ] = None ,
@@ -680,21 +703,60 @@ def _download_params_via_mavftp(
680703 """
681704 if self .master is None :
682705 return {}, ParDict ()
683- mavftp = MAVFTP (self .master , target_system = self .master .target_system , target_component = self .master .target_component )
706+
707+ # Create more robust MAVFTP settings for parameter download
708+ # STM32 F4 controllers under workload need longer timeouts
709+ mavftp_settings = self ._create_robust_mavftp_settings ()
710+
711+ mavftp = MAVFTP (
712+ self .master ,
713+ target_system = self .master .target_system ,
714+ target_component = self .master .target_component ,
715+ settings = mavftp_settings ,
716+ )
684717
685718 def get_params_progress_callback (completion : float ) -> None :
686719 if progress_callback is not None and completion is not None :
687720 progress_callback (int (completion * 100 ), 100 )
688721
689722 complete_param_filename = str (parameter_values_filename ) if parameter_values_filename else "complete.param"
690723 default_param_filename = str (parameter_defaults_filename ) if parameter_defaults_filename else "00_default.param"
691- mavftp .cmd_getparams ([complete_param_filename , default_param_filename ], progress_callback = get_params_progress_callback )
692- ret = mavftp .process_ftp_reply ("getparams" , timeout = 40 ) # on slow links it might take a long time
693- pdict : dict [str , float ] = {}
694- defdict : ParDict = ParDict ()
724+
725+ # Retry logic for increased robustness with STM32 F4 controllers under workload
726+ max_retries = 3
727+ base_timeout = 15
728+
729+ for attempt in range (max_retries ):
730+ try :
731+ mavftp .cmd_getparams (
732+ [complete_param_filename , default_param_filename ], progress_callback = get_params_progress_callback
733+ )
734+ # Progressive timeout increase for each retry attempt
735+ timeout = base_timeout * (2 ** attempt ) # 15s, 30s, 60s
736+ logging_info (_ ("Attempt %d/%d: Requesting parameters with %ds timeout" ), attempt + 1 , max_retries , timeout )
737+ ret = mavftp .process_ftp_reply ("getparams" , timeout = timeout )
738+
739+ if ret .error_code == 0 :
740+ break # Success, exit retry loop
741+
742+ if attempt < max_retries - 1 : # Don't sleep after last attempt
743+ sleep_time = 2 ** attempt # 1s, 2s, 4s exponential backoff
744+ logging_warning (_ ("Parameter download attempt %d failed, retrying in %ds..." ), attempt + 1 , sleep_time )
745+ time_sleep (sleep_time )
746+ else :
747+ logging_error (_ ("All %d parameter download attempts failed" ), max_retries )
748+
749+ except Exception as e : # pylint: disable=broad-exception-caught
750+ logging_error (_ ("Exception during parameter download attempt %d: %s" ), attempt + 1 , str (e ))
751+ if attempt < max_retries - 1 :
752+ sleep_time = 2 ** attempt
753+ time_sleep (sleep_time )
695754
696755 # add a file sync operation to ensure the file is completely written
697756 time_sleep (0.3 )
757+
758+ pdict : dict [str , float ] = {}
759+ defdict : ParDict = ParDict ()
698760 if ret .error_code == 0 :
699761 # load the parameters from the file
700762 par_dict = ParDict .from_file (complete_param_filename )
@@ -1205,14 +1267,23 @@ def upload_file(
12051267 """Upload a file to the flight controller."""
12061268 if self .master is None :
12071269 return False
1208- mavftp = MAVFTP (self .master , target_system = self .master .target_system , target_component = self .master .target_component )
1270+
1271+ # Use robust MAVFTP settings for better reliability with STM32 F4 controllers
1272+ mavftp_settings = self ._create_robust_mavftp_settings ()
1273+ mavftp = MAVFTP (
1274+ self .master ,
1275+ target_system = self .master .target_system ,
1276+ target_component = self .master .target_component ,
1277+ settings = mavftp_settings ,
1278+ )
12091279
12101280 def put_progress_callback (completion : float ) -> None :
12111281 if progress_callback is not None and completion is not None :
12121282 progress_callback (int (completion * 100 ), 100 )
12131283
12141284 mavftp .cmd_put ([local_filename , remote_filename ], progress_callback = put_progress_callback )
1215- ret = mavftp .process_ftp_reply ("CreateFile" , timeout = 10 )
1285+ # Increased timeout for better reliability
1286+ ret = mavftp .process_ftp_reply ("CreateFile" , timeout = 20 )
12161287 if ret .error_code != 0 :
12171288 ret .display_message ()
12181289 return ret .error_code == 0
@@ -1230,7 +1301,14 @@ def download_last_flight_log(
12301301 logging_error (error_msg )
12311302 return False
12321303
1233- mavftp = MAVFTP (self .master , target_system = self .master .target_system , target_component = self .master .target_component )
1304+ # Use robust MAVFTP settings for better reliability with STM32 F4 controllers
1305+ mavftp_settings = self ._create_robust_mavftp_settings ()
1306+ mavftp = MAVFTP (
1307+ self .master ,
1308+ target_system = self .master .target_system ,
1309+ target_component = self .master .target_component ,
1310+ settings = mavftp_settings ,
1311+ )
12341312
12351313 def get_progress_callback (completion : float ) -> None :
12361314 if progress_callback is not None and completion is not None :
0 commit comments