@@ -613,6 +613,37 @@ def heartbeat_is_from_autopilot(self, m):
613
613
614
614
return True
615
615
616
+ def should_show_command_ack (self , m ):
617
+ '''returns true if we should display some text on the console for m'''
618
+ if m .target_component in [mavutil .mavlink .MAV_COMP_ID_MAVCAN ]:
619
+ # too noisy?
620
+ return False
621
+
622
+ if m .command in frozenset ([
623
+ mavutil .mavlink .MAV_CMD_GET_HOME_POSITION ,
624
+ mavutil .mavlink .MAV_CMD_DO_DIGICAM_CONTROL
625
+ ]):
626
+ # too noisy?
627
+ return False
628
+
629
+ if self .settings .all_vehicle_command_acks :
630
+ # we're showing everything
631
+ return True
632
+
633
+ if m .target_system == 0 :
634
+ return True
635
+
636
+ if m .target_system != self .settings .source_system :
637
+ return False
638
+
639
+ if m .target_component == 0 :
640
+ return True
641
+
642
+ if m .target_component != self .settings .source_component :
643
+ return False
644
+
645
+ return True
646
+
616
647
def master_msg_handling (self , m , master ):
617
648
'''link message handling for an upstream link'''
618
649
if not self .message_is_from_primary_vehicle (m ):
@@ -827,11 +858,9 @@ def accumulated_statustext(self):
827
858
cmd = cmd [8 :]
828
859
res = mavutil .mavlink .enums ["MAV_RESULT" ][m .result ].name
829
860
res = res [11 :]
830
- if (m .target_component not in [mavutil .mavlink .MAV_COMP_ID_MAVCAN ] and
831
- m .command not in [mavutil .mavlink .MAV_CMD_GET_HOME_POSITION ,
832
- mavutil .mavlink .MAV_CMD_DO_DIGICAM_CONTROL ]):
861
+ if self .should_show_command_ack (m ):
833
862
self .mpstate .console .writeln ("Got COMMAND_ACK: %s: %s" % (cmd , res ))
834
- except Exception :
863
+ except KeyError as e :
835
864
self .mpstate .console .writeln ("Got MAVLink msg: %s" % m )
836
865
837
866
if m .command == mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION :
0 commit comments