@@ -705,6 +705,37 @@ def heartbeat_is_from_autopilot(self, m):
705
705
continue
706
706
mav_type_planes .append (attr )
707
707
708
+ def should_show_command_ack (self , m ):
709
+ '''returns true if we should display some text on the console for m'''
710
+ if m .target_component in [mavutil .mavlink .MAV_COMP_ID_MAVCAN ]:
711
+ # too noisy?
712
+ return False
713
+
714
+ if m .command in frozenset ([
715
+ mavutil .mavlink .MAV_CMD_GET_HOME_POSITION ,
716
+ mavutil .mavlink .MAV_CMD_DO_DIGICAM_CONTROL
717
+ ]):
718
+ # too noisy?
719
+ return False
720
+
721
+ if self .settings .all_vehicle_command_acks :
722
+ # we're showing everything
723
+ return True
724
+
725
+ if m .target_system == 0 :
726
+ return True
727
+
728
+ if m .target_system != self .settings .source_system :
729
+ return False
730
+
731
+ if m .target_component == 0 :
732
+ return True
733
+
734
+ if m .target_component != self .settings .source_component :
735
+ return False
736
+
737
+ return True
738
+
708
739
def master_msg_handling (self , m , master ):
709
740
'''link message handling for an upstream link'''
710
741
@@ -921,11 +952,9 @@ def accumulated_statustext(self):
921
952
cmd = cmd [8 :]
922
953
res = mavutil .mavlink .enums ["MAV_RESULT" ][m .result ].name
923
954
res = res [11 :]
924
- if (m .target_component not in [mavutil .mavlink .MAV_COMP_ID_MAVCAN ] and
925
- m .command not in [mavutil .mavlink .MAV_CMD_GET_HOME_POSITION ,
926
- mavutil .mavlink .MAV_CMD_DO_DIGICAM_CONTROL ]):
927
- self .mpstate .console .writeln ("Got COMMAND_ACK: %s: %s" % (cmd , res ))
928
- except Exception :
955
+ if self .should_show_command_ack (m ):
956
+ self .mpstate .console .writeln ("Got COMMAND_ACK: %s: %s" % (cmd , res )) # noqa
957
+ except KeyError :
929
958
self .mpstate .console .writeln ("Got MAVLink msg: %s" % m )
930
959
931
960
if m .command == mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION :
0 commit comments