Skip to content

Commit 8554384

Browse files
committed
link: add option to suppress printing of ACKs from other systems
1 parent 9d13040 commit 8554384

File tree

2 files changed

+39
-8
lines changed

2 files changed

+39
-8
lines changed

MAVProxy/mavproxy.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -304,6 +304,8 @@ def __init__(self):
304304

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

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

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

MAVProxy/modules/mavproxy_link.py

Lines changed: 37 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -711,6 +711,40 @@ def heartbeat_is_from_autopilot(self, m):
711711
continue
712712
mav_type_planes.append(attr)
713713

714+
def should_show_command_ack(self, m):
715+
'''returns true if we should display some text on the console for m'''
716+
if m.target_component in [mavutil.mavlink.MAV_COMP_ID_MAVCAN]:
717+
# too noisy?
718+
return False
719+
720+
if m.command in frozenset([
721+
mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,
722+
mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
723+
mavutil.mavlink.MAV_CMD_SET_CAMERA_MODE,
724+
mavutil.mavlink.MAV_CMD_SET_CAMERA_ZOOM,
725+
mavutil.mavlink.MAV_CMD_SET_CAMERA_FOCUS,
726+
]):
727+
# too noisy?
728+
return False
729+
730+
if self.settings.all_vehicle_command_acks:
731+
# we're showing everything
732+
return True
733+
734+
if m.target_system == 0:
735+
return True
736+
737+
if m.target_system != self.settings.source_system:
738+
return False
739+
740+
if m.target_component == 0:
741+
return True
742+
743+
if m.target_component != self.settings.source_component:
744+
return False
745+
746+
return True
747+
714748
def master_msg_handling(self, m, master):
715749
'''link message handling for an upstream link'''
716750

@@ -927,14 +961,9 @@ def accumulated_statustext(self):
927961
cmd = cmd[8:]
928962
res = mavutil.mavlink.enums["MAV_RESULT"][m.result].name
929963
res = res[11:]
930-
if (m.target_component not in [mavutil.mavlink.MAV_COMP_ID_MAVCAN] and
931-
m.command not in [mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,
932-
mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
933-
mavutil.mavlink.MAV_CMD_SET_CAMERA_MODE,
934-
mavutil.mavlink.MAV_CMD_SET_CAMERA_ZOOM,
935-
mavutil.mavlink.MAV_CMD_SET_CAMERA_FOCUS]):
936-
self.mpstate.console.writeln("Got COMMAND_ACK: %s: %s" % (cmd, res))
937-
except Exception:
964+
if self.should_show_command_ack(m):
965+
self.mpstate.console.writeln("Got COMMAND_ACK: %s: %s" % (cmd, res)) # noqa
966+
except KeyError:
938967
self.mpstate.console.writeln("Got MAVLink msg: %s" % m)
939968

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

0 commit comments

Comments
 (0)