@@ -722,6 +722,41 @@ def heartbeat_is_from_autopilot(self, m):
722722 continue
723723 mav_type_planes .append (attr )
724724
725+ def should_show_command_ack (self , m ):
726+ '''returns true if we should display some text on the console for m'''
727+ if m .target_component in [mavutil .mavlink .MAV_COMP_ID_MAVCAN ]:
728+ # too noisy?
729+ return False
730+
731+ if m .command in frozenset ([
732+ mavutil .mavlink .MAV_CMD_GET_HOME_POSITION ,
733+ mavutil .mavlink .MAV_CMD_DO_DIGICAM_CONTROL ,
734+ mavutil .mavlink .MAV_CMD_SET_CAMERA_MODE ,
735+ mavutil .mavlink .MAV_CMD_SET_CAMERA_ZOOM ,
736+ mavutil .mavlink .MAV_CMD_SET_CAMERA_FOCUS ,
737+ mavutil .mavlink .MAV_CMD_CAN_FORWARD ,
738+ ]):
739+ # too noisy?
740+ return False
741+
742+ if self .settings .all_vehicle_command_acks :
743+ # we're showing everything
744+ return True
745+
746+ if m .target_system == 0 :
747+ return True
748+
749+ if m .target_system != self .settings .source_system :
750+ return False
751+
752+ if m .target_component == 0 :
753+ return True
754+
755+ if m .target_component != self .settings .source_component :
756+ return False
757+
758+ return True
759+
725760 def master_msg_handling (self , m , master ):
726761 '''link message handling for an upstream link'''
727762
@@ -938,15 +973,9 @@ def accumulated_statustext(self):
938973 cmd = cmd [8 :]
939974 res = mavutil .mavlink .enums ["MAV_RESULT" ][m .result ].name
940975 res = res [11 :]
941- if (m .target_component not in [mavutil .mavlink .MAV_COMP_ID_MAVCAN ] and
942- m .command not in [mavutil .mavlink .MAV_CMD_GET_HOME_POSITION ,
943- mavutil .mavlink .MAV_CMD_DO_DIGICAM_CONTROL ,
944- mavutil .mavlink .MAV_CMD_SET_CAMERA_MODE ,
945- mavutil .mavlink .MAV_CMD_SET_CAMERA_ZOOM ,
946- mavutil .mavlink .MAV_CMD_CAN_FORWARD ,
947- mavutil .mavlink .MAV_CMD_SET_CAMERA_FOCUS ]):
948- self .mpstate .console .writeln ("Got COMMAND_ACK: %s: %s" % (cmd , res ))
949- except Exception :
976+ if self .should_show_command_ack (m ):
977+ self .mpstate .console .writeln ("Got COMMAND_ACK: %s: %s" % (cmd , res )) # noqa
978+ except KeyError :
950979 self .mpstate .console .writeln ("Got MAVLink msg: %s" % m )
951980
952981 if m .command == mavutil .mavlink .MAV_CMD_PREFLIGHT_CALIBRATION :
0 commit comments