Skip to content

Commit a9365f1

Browse files
committed
link: add option to suppress printing of ACKs from other systems
1 parent 037ca95 commit a9365f1

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
@@ -303,6 +303,8 @@ def __init__(self):
303303

304304
MPSetting('vehicle_name', str, '', 'Vehicle Name', tab='Vehicle'),
305305

306+
MPSetting('all_vehicle_command_acks', bool, True, 'Show COMMAND_ACKs even if they are targetted at other vehicles'),
307+
306308
MPSetting('sys_status_error_warn_interval', int, 30, 'interval to warn of autopilot software failure'),
307309

308310
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
@@ -705,6 +705,37 @@ def heartbeat_is_from_autopilot(self, m):
705705
continue
706706
mav_type_planes.append(attr)
707707

708+
def should_show_command_ack(self, m):
709+
'''returns true if we should display some text on the console for m'''
710+
if m.target_component in [mavutil.mavlink.MAV_COMP_ID_MAVCAN]:
711+
# too noisy?
712+
return False
713+
714+
if m.command in frozenset([
715+
mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,
716+
mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL
717+
]):
718+
# too noisy?
719+
return False
720+
721+
if self.settings.all_vehicle_command_acks:
722+
# we're showing everything
723+
return True
724+
725+
if m.target_system == 0:
726+
return True
727+
728+
if m.target_system != self.settings.source_system:
729+
return False
730+
731+
if m.target_component == 0:
732+
return True
733+
734+
if m.target_component != self.settings.source_component:
735+
return False
736+
737+
return True
738+
708739
def master_msg_handling(self, m, master):
709740
'''link message handling for an upstream link'''
710741

@@ -921,11 +952,9 @@ def accumulated_statustext(self):
921952
cmd = cmd[8:]
922953
res = mavutil.mavlink.enums["MAV_RESULT"][m.result].name
923954
res = res[11:]
924-
if (m.target_component not in [mavutil.mavlink.MAV_COMP_ID_MAVCAN] and
925-
m.command not in [mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,
926-
mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL]):
955+
if self.should_show_command_ack(m):
927956
self.mpstate.console.writeln("Got COMMAND_ACK: %s: %s" % (cmd, res))
928-
except Exception:
957+
except KeyError as e:
929958
self.mpstate.console.writeln("Got MAVLink msg: %s" % m)
930959

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

0 commit comments

Comments
 (0)