31
31
from ardupilot_methodic_configurator import _
32
32
from ardupilot_methodic_configurator .argparse_check_range import CheckRange
33
33
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
35
35
from ardupilot_methodic_configurator .data_model_par_dict import ParDict
36
36
37
37
# pylint: disable=too-many-lines
@@ -653,7 +653,30 @@ def _download_params_via_mavlink(
653
653
break
654
654
return parameters
655
655
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
657
680
self ,
658
681
progress_callback : Union [None , Callable [[int , int ], None ]] = None ,
659
682
parameter_values_filename : Optional [Path ] = None ,
@@ -676,21 +699,60 @@ def _download_params_via_mavftp(
676
699
"""
677
700
if self .master is None :
678
701
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
+ )
680
713
681
714
def get_params_progress_callback (completion : float ) -> None :
682
715
if progress_callback is not None and completion is not None :
683
716
progress_callback (int (completion * 100 ), 100 )
684
717
685
718
complete_param_filename = str (parameter_values_filename ) if parameter_values_filename else "complete.param"
686
719
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 )
691
750
692
751
# add a file sync operation to ensure the file is completely written
693
752
time_sleep (0.3 )
753
+
754
+ pdict : dict [str , float ] = {}
755
+ defdict : ParDict = ParDict ()
694
756
if ret .error_code == 0 :
695
757
# load the parameters from the file
696
758
par_dict = ParDict .from_file (complete_param_filename )
@@ -1152,14 +1214,23 @@ def upload_file(
1152
1214
"""Upload a file to the flight controller."""
1153
1215
if self .master is None :
1154
1216
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
+ )
1156
1226
1157
1227
def put_progress_callback (completion : float ) -> None :
1158
1228
if progress_callback is not None and completion is not None :
1159
1229
progress_callback (int (completion * 100 ), 100 )
1160
1230
1161
1231
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 )
1163
1234
if ret .error_code != 0 :
1164
1235
ret .display_message ()
1165
1236
return ret .error_code == 0
@@ -1177,7 +1248,14 @@ def download_last_flight_log(
1177
1248
logging_error (error_msg )
1178
1249
return False
1179
1250
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
+ )
1181
1259
1182
1260
def get_progress_callback (completion : float ) -> None :
1183
1261
if progress_callback is not None and completion is not None :
0 commit comments