@@ -538,6 +538,34 @@ def emit_accumulated_statustext(self, key, id, pending):
538538 self .status .last_apm_msg_time = time .time ()
539539 del self .status .statustexts_by_sysidcompid [key ][id ]
540540
541+ def should_show_command_ack (self , m ):
542+ '''returns true if we should display some text on the console for m'''
543+ if m .target_component in [mavutil .mavlink .MAV_COMP_ID_MAVCAN ]:
544+ # too noisy?
545+ return False
546+
547+ if m .command in [mavutil .mavlink .MAV_CMD_GET_HOME_POSITION ]:
548+ # too noisy?
549+ return False
550+
551+ if self .settings .all_command_acks :
552+ # we're showing everything
553+ return True
554+
555+ if m .target_system == 0 :
556+ return True
557+
558+ if m .target_system != self .settings .source_system :
559+ return False
560+
561+ if m .target_component == 0 :
562+ return True
563+
564+ if m .target_component != self .settings .source_component :
565+ return False
566+
567+ return True
568+
541569 def master_msg_handling (self , m , master ):
542570 '''link message handling for an upstream link'''
543571 if self .settings .target_system != 0 and m .get_srcSystem () != self .settings .target_system :
@@ -744,10 +772,9 @@ def accumulated_statustext(self):
744772 cmd = cmd [8 :]
745773 res = mavutil .mavlink .enums ["MAV_RESULT" ][m .result ].name
746774 res = res [11 :]
747- if (m .target_component not in [mavutil .mavlink .MAV_COMP_ID_MAVCAN ] and
748- m .command not in [mavutil .mavlink .MAV_CMD_GET_HOME_POSITION ]):
775+ if self .should_show_command_ack (m ):
749776 self .mpstate .console .writeln ("Got COMMAND_ACK: %s: %s" % (cmd , res ))
750- except Exception :
777+ except KeyError as e :
751778 self .mpstate .console .writeln ("Got MAVLink msg: %s" % m )
752779
753780 if m .command == mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION :
0 commit comments