From 8f3bca3919922774f6861357b6109bcb6ee9a86d Mon Sep 17 00:00:00 2001 From: magate <69254089+magate@users.noreply.github.com> Date: Fri, 4 Oct 2024 16:30:48 -0700 Subject: [PATCH] mavproxy_messagerate: do special handling for reset and stop set --- MAVProxy/modules/mavproxy_messagerate.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/MAVProxy/modules/mavproxy_messagerate.py b/MAVProxy/modules/mavproxy_messagerate.py index 78f6c0ad75..73bd1c1343 100644 --- a/MAVProxy/modules/mavproxy_messagerate.py +++ b/MAVProxy/modules/mavproxy_messagerate.py @@ -61,6 +61,8 @@ def cmd_messagerate(self, args): return message_name = args[1] message_rate = float(args[2]) + # Special handling for -1 and 0 which correspond to "stop sending" and "reset to default rate" + message_rate = message_rate if message_rate <= 0 else 1E6/message_rate priority = 0 if len(args) > 3: priority = int(args[3]) @@ -74,7 +76,7 @@ def cmd_messagerate(self, args): self.settings.target_component, mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, 0, - msg_id, (int) (1E6/message_rate), priority, 0, 0, 0, 0) + msg_id, (int) (message_rate), priority, 0, 0, 0, 0) return print("Unknown message ID:%s" % message_name)