@@ -158,24 +158,30 @@ def handle_PARAM_VALUE(self, m, value):
158158
159159 return True
160160
161+ def print_failed_to_set (self , reason ):
162+ print (f"Failed to set { self .name } to { self .value } : { reason } " )
163+
161164 def print_expired_message (self ):
162165 reason = ""
163166 if self .last_value_received is None :
164- reason = " (no PARAM_VALUE received)"
167+ reason = "(no PARAM_VALUE received)"
165168 else :
166- reason = f" (invalid returned value { self .last_value_received } )"
167- print ( f"Failed to set { self .name } to { self . value } { reason } " )
169+ reason = f"(invalid returned value { self .last_value_received } )"
170+ self .print_failed_to_set ( reason )
168171
169- def run_parameter_set_queue (self ):
170- # firstly move anything from the input queue into our
171- # collection of things to send:
172+ def move_input_queue_to_collections_of_things_to_send (self ):
172173 try :
173174 while True :
174175 new_parameter_to_set = self .parameters_to_set_input_queue .get (block = False )
175176 self .parameters_to_set [new_parameter_to_set .name ] = new_parameter_to_set
176177 except Empty :
177178 pass
178179
180+ def run_parameter_set_queue (self ):
181+ # firstly move anything from the input queue into our
182+ # collection of things to send:
183+ self .move_input_queue_to_collections_of_things_to_send ()
184+
179185 # now send any parameter-sets which are due to be sent out,
180186 # either because they are new or because we need to retry:
181187 count = 0
@@ -242,6 +248,47 @@ def handle_px4_param_value(self, m):
242248 self .param_types [m .param_id .upper ()] = m .param_type
243249 return value
244250
251+ def handle_param_error (self , m ):
252+ # ignore any param_error not targeted at us:
253+ if m .target_system != self .mpstate .settings .source_system :
254+ return
255+ if m .target_component != self .mpstate .settings .source_component :
256+ return
257+
258+ try :
259+ error_desc = mavutil .mavlink .enums ['MAV_PARAM_ERROR' ][m .error ].name
260+ except KeyError :
261+ error_desc = m .error
262+
263+ # check for failed fetches
264+ if self .fetch_set is not None :
265+ if m .param_index in self .fetch_set :
266+ self .fetch_set .discard (m .param_index )
267+ self .mpstate .console .writeln (f"Parameter[{ m .param_index } ] fetch failed: { error_desc } " )
268+ return
269+
270+ if self .fetch_one .get (m .param_id , 0 ) > 0 :
271+ self .fetch_one [m .param_id ] -= 1 # set-to-zero?
272+ self .mpstate .console .writeln (f"Parameter[{ m .param_id } ] fetch failed: { error_desc } " )
273+ return
274+
275+ # check for failed sets
276+ if m .param_id != "" :
277+ # firstly move anything from the input queue into our
278+ # collection of things to send:
279+ self .move_input_queue_to_collections_of_things_to_send ()
280+
281+ for (key , parameter_to_set ) in self .parameters_to_set .items ():
282+ if parameter_to_set .name != m .param_id :
283+ continue
284+ try :
285+ error_desc = mavutil .mavlink .enums ['MAV_PARAM_ERROR' ][m .error ].name
286+ except KeyError :
287+ error_desc = m .error
288+ parameter_to_set .print_failed_to_set (error_desc )
289+ del self .parameters_to_set [key ]
290+ break
291+
245292 def handle_mavlink_packet (self , master , m ):
246293 '''handle an incoming mavlink packet'''
247294 if m .get_type () == 'PARAM_VALUE' :
@@ -289,6 +336,9 @@ def handle_mavlink_packet(self, master, m):
289336 # remember autopilot types so we can handle PX4 parameters
290337 self .autopilot_type_by_sysid [m .get_srcSystem ()] = m .autopilot
291338
339+ elif m .get_type () == 'PARAM_ERROR' :
340+ self .handle_param_error (m )
341+
292342 def fetch_check (self , master , force = False ):
293343 '''check for missing parameters periodically'''
294344 if self .param_period .trigger () or force :
0 commit comments