@@ -696,7 +696,6 @@ def upload_params_that_require_reset(self, selected_params: dict) -> None:
696696 # Write each selected parameter to the flight controller
697697 for param_name , param in selected_params .items ():
698698 try :
699- logging_info (_ ("Parameter %s set to %f" ), param_name , param .value )
700699 if param_name not in self .flight_controller .fc_parameters or not is_within_tolerance (
701700 self .flight_controller .fc_parameters [param_name ], param .value
702701 ):
@@ -776,25 +775,52 @@ def on_upload_selected_click(self) -> None:
776775 self .on_skip_click ()
777776
778777 # This function can recurse multiple times if there is an upload error
779- def upload_selected_params (self , selected_params : dict ) -> None :
778+ def upload_selected_params (self , selected_params : dict ) -> None : # pylint: disable=too-many-branches
780779 logging_info (_ ("Uploading %d selected %s parameters to flight controller..." ), len (selected_params ), self .current_file )
781780
782781 self .upload_params_that_require_reset (selected_params )
783782
784783 # Write each selected parameter to the flight controller
784+ nr_changed = 0
785+ nr_unchanged = 0
785786 for param_name , param in selected_params .items ():
786787 try :
787788 self .flight_controller .set_param (param_name , param .value )
788- logging_info (_ ("Parameter %s set to %f" ), param_name , param .value )
789789 if param_name not in self .flight_controller .fc_parameters or not is_within_tolerance (
790790 self .flight_controller .fc_parameters [param_name ], param .value
791791 ):
792792 self .at_least_one_changed_parameter_written = True
793+ if param_name in self .flight_controller .fc_parameters :
794+ logging_info (
795+ _ ("Parameter %s changed from %f to %f" ),
796+ param_name ,
797+ self .flight_controller .fc_parameters [param_name ],
798+ param .value ,
799+ )
800+ else :
801+ logging_info (
802+ _ ("Parameter %s changed to %f" ),
803+ param_name ,
804+ param .value ,
805+ )
806+ nr_changed += 1
807+ else :
808+ logging_info (_ ("Parameter %s unchanged from %f" ), param_name , param .value )
809+ nr_unchanged += 1
793810 except ValueError as _e : # noqa: PERF203
794811 error_msg = _ ("Failed to set parameter {param_name}: {_e}" ).format (** locals ())
795812 logging_error (error_msg )
796813 messagebox .showerror (_ ("ArduPilot methodic configurator" ), error_msg )
797814
815+ changed_msg = _ ("%d FC parameter(s) changed value" ) % nr_changed if nr_changed else ""
816+ unchanged_msg = (
817+ _ ("%d FC parameter(s) already had the value defined in this configuration step" ) % nr_unchanged
818+ if nr_unchanged
819+ else ""
820+ )
821+ msg = changed_msg + (", " if nr_changed and nr_unchanged else "" ) + unchanged_msg
822+ logging_info (msg )
823+
798824 if self .at_least_one_changed_parameter_written :
799825 # Re-download all parameters, in case one of them changed, and validate that all uploads were successful
800826 self .download_flight_controller_parameters (redownload = True )
0 commit comments