Skip to content

Commit 5279423

Browse files
committed
link: add option to suppress printing of ACKs from other systems
1 parent 3192cae commit 5279423

File tree

2 files changed

+35
-4
lines changed

2 files changed

+35
-4
lines changed

Diff for: MAVProxy/mavproxy.py

+2
Original file line numberDiff line numberDiff line change
@@ -289,6 +289,8 @@ def __init__(self):
289289

290290
MPSetting('vehicle_name', str, '', 'Vehicle Name', tab='Vehicle'),
291291

292+
MPSetting('all_vehicle_command_acks', bool, True, 'Show COMMAND_ACKs even if they are targetted at other vehicles'),
293+
292294
MPSetting('sys_status_error_warn_interval', int, 30, 'interval to warn of autopilot software failure'),
293295

294296
MPSetting('inhibit_screensaver_when_armed', bool, False, 'inhibit screensaver while vehicle armed'),

Diff for: MAVProxy/modules/mavproxy_link.py

+33-4
Original file line numberDiff line numberDiff line change
@@ -613,6 +613,37 @@ def heartbeat_is_from_autopilot(self, m):
613613

614614
return True
615615

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+
616647
def master_msg_handling(self, m, master):
617648
'''link message handling for an upstream link'''
618649
if not self.message_is_from_primary_vehicle(m):
@@ -827,11 +858,9 @@ def accumulated_statustext(self):
827858
cmd = cmd[8:]
828859
res = mavutil.mavlink.enums["MAV_RESULT"][m.result].name
829860
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):
833862
self.mpstate.console.writeln("Got COMMAND_ACK: %s: %s" % (cmd, res))
834-
except Exception:
863+
except KeyError as e:
835864
self.mpstate.console.writeln("Got MAVLink msg: %s" % m)
836865

837866
if m.command == mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION:

0 commit comments

Comments
 (0)