From a9365f1db8063915c4a34498fac6897dba043224 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 19 Apr 2022 16:48:10 +1000 Subject: [PATCH] link: add option to suppress printing of ACKs from other systems --- MAVProxy/mavproxy.py | 2 ++ MAVProxy/modules/mavproxy_link.py | 37 +++++++++++++++++++++++++++---- 2 files changed, 35 insertions(+), 4 deletions(-) diff --git a/MAVProxy/mavproxy.py b/MAVProxy/mavproxy.py index fab768c50d..fbfe202f07 100755 --- a/MAVProxy/mavproxy.py +++ b/MAVProxy/mavproxy.py @@ -303,6 +303,8 @@ def __init__(self): MPSetting('vehicle_name', str, '', 'Vehicle Name', tab='Vehicle'), + MPSetting('all_vehicle_command_acks', bool, True, 'Show COMMAND_ACKs even if they are targetted at other vehicles'), + MPSetting('sys_status_error_warn_interval', int, 30, 'interval to warn of autopilot software failure'), MPSetting('inhibit_screensaver_when_armed', bool, False, 'inhibit screensaver while vehicle armed'), diff --git a/MAVProxy/modules/mavproxy_link.py b/MAVProxy/modules/mavproxy_link.py index ecb4fc34ef..f73597c7e6 100644 --- a/MAVProxy/modules/mavproxy_link.py +++ b/MAVProxy/modules/mavproxy_link.py @@ -705,6 +705,37 @@ def heartbeat_is_from_autopilot(self, m): continue mav_type_planes.append(attr) + def should_show_command_ack(self, m): + '''returns true if we should display some text on the console for m''' + if m.target_component in [mavutil.mavlink.MAV_COMP_ID_MAVCAN]: + # too noisy? + return False + + if m.command in frozenset([ + mavutil.mavlink.MAV_CMD_GET_HOME_POSITION, + mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL + ]): + # too noisy? + return False + + if self.settings.all_vehicle_command_acks: + # we're showing everything + return True + + if m.target_system == 0: + return True + + if m.target_system != self.settings.source_system: + return False + + if m.target_component == 0: + return True + + if m.target_component != self.settings.source_component: + return False + + return True + def master_msg_handling(self, m, master): '''link message handling for an upstream link''' @@ -921,11 +952,9 @@ def accumulated_statustext(self): cmd = cmd[8:] res = mavutil.mavlink.enums["MAV_RESULT"][m.result].name res = res[11:] - if (m.target_component not in [mavutil.mavlink.MAV_COMP_ID_MAVCAN] and - m.command not in [mavutil.mavlink.MAV_CMD_GET_HOME_POSITION, - mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL]): + if self.should_show_command_ack(m): self.mpstate.console.writeln("Got COMMAND_ACK: %s: %s" % (cmd, res)) - except Exception: + except KeyError as e: self.mpstate.console.writeln("Got MAVLink msg: %s" % m) if m.command == mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION: