From c4b11739d6d7ded7ad5e5184b05f67fc16f35870 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 | 33 ++++++++++++++++++++++++++++--- 2 files changed, 32 insertions(+), 3 deletions(-) diff --git a/MAVProxy/mavproxy.py b/MAVProxy/mavproxy.py index 06d666a0d4..91b38a1dbb 100644 --- a/MAVProxy/mavproxy.py +++ b/MAVProxy/mavproxy.py @@ -283,6 +283,8 @@ def __init__(self): MPSetting('vehicle_name', str, '', 'Vehicle Name', tab='Vehicle'), + MPSetting('all_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 7e2aa058c2..4eaae0c955 100644 --- a/MAVProxy/modules/mavproxy_link.py +++ b/MAVProxy/modules/mavproxy_link.py @@ -538,6 +538,34 @@ def emit_accumulated_statustext(self, key, id, pending): self.status.last_apm_msg_time = time.time() del self.status.statustexts_by_sysidcompid[key][id] + 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 [mavutil.mavlink.MAV_CMD_GET_HOME_POSITION]: + # too noisy? + return False + + if self.settings.all_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''' if self.settings.target_system != 0 and m.get_srcSystem() != self.settings.target_system: @@ -744,10 +772,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]): + 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: