Skip to content

Commit

Permalink
mavproxy_messagerate: do special handling for reset and stop set
Browse files Browse the repository at this point in the history
  • Loading branch information
magate authored and peterbarker committed Oct 7, 2024
1 parent 3c240f4 commit 8f3bca3
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion MAVProxy/modules/mavproxy_messagerate.py
Original file line number Diff line number Diff line change
Expand Up @@ -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])
Expand All @@ -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)

Expand Down

0 comments on commit 8f3bca3

Please sign in to comment.