mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_Scripting: update so mavlink init intent matches behavior
RX message ID buffer sizes have been shrunk to the amount actually used.
This commit is contained in:
parent
fe3f12dc87
commit
962616a76f
@ -2309,8 +2309,8 @@ local function mavlink_receiver()
|
||||
|
||||
msg_map[NAMED_VALUE_FLOAT_msgid] = "NAMED_VALUE_FLOAT"
|
||||
|
||||
-- initialise mavlink rx with number of messages, and buffer depth
|
||||
mavlink.init(1, 10)
|
||||
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
|
||||
mavlink.init(10, 1)
|
||||
|
||||
-- register message id to receive
|
||||
mavlink.register_rx_msgid(NAMED_VALUE_FLOAT_msgid)
|
||||
|
@ -103,8 +103,8 @@ local GLOBAL_POSITION_INT_ID = 33
|
||||
local msg_map = {}
|
||||
msg_map[GLOBAL_POSITION_INT_ID] = "GLOBAL_POSITION_INT"
|
||||
|
||||
-- initialize MAVLink rx with number of messages, and buffer depth
|
||||
mavlink:init(2, 5)
|
||||
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
|
||||
mavlink:init(5, 1)
|
||||
|
||||
-- register message id to receive
|
||||
mavlink:register_rx_msgid(GLOBAL_POSITION_INT_ID)
|
||||
|
@ -43,9 +43,6 @@ local FOLT_ENABLE = bind_add_param("ENABLE", 1, 1)
|
||||
--]]
|
||||
local FOLT_MAV_CHAN = bind_add_param("MAV_CHAN", 2, 0)
|
||||
|
||||
-- initialize MAVLink rx with number of messages, and buffer depth
|
||||
mavlink:init(2, 5)
|
||||
|
||||
-- send FOLLOW_TARGET message
|
||||
local function send_follow_target_msg()
|
||||
|
||||
|
@ -51,8 +51,6 @@ local last_roi_switch_pos = 0 -- last known rc roi switch position. U
|
||||
local success_count = 0 -- count of the number of POI calculations (sent to GCS in CAMERA_FEEDBACK message)
|
||||
|
||||
-- mavlink message definition
|
||||
-- initialise mavlink rx with number of messages, and buffer depth
|
||||
mavlink.init(1, 10)
|
||||
local messages = {}
|
||||
messages[180] = { -- CAMERA_FEEDBACK
|
||||
{ "time_usec", "<I8" },
|
||||
|
@ -30,8 +30,8 @@ local MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246
|
||||
local MAV_RESULT_ACCEPTED = 0
|
||||
local MAV_RESULT_FAILED = 4
|
||||
|
||||
-- Initialize MAVLink rx with number of messages, and buffer depth
|
||||
mavlink:init(1, 10)
|
||||
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
|
||||
mavlink:init(10, 1)
|
||||
-- Register message id to receive
|
||||
mavlink:register_rx_msgid(COMMAND_LONG_ID)
|
||||
-- Block MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN so we can handle the ACK
|
||||
|
@ -9,8 +9,8 @@ local msg_map = {}
|
||||
msg_map[COMMAND_ACK_ID] = "COMMAND_ACK"
|
||||
msg_map[COMMAND_LONG_ID] = "COMMAND_LONG"
|
||||
|
||||
-- initialize MAVLink rx with number of messages, and buffer depth
|
||||
mavlink:init(1, 10)
|
||||
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
|
||||
mavlink:init(10, 1)
|
||||
|
||||
-- register message id to receive
|
||||
mavlink:register_rx_msgid(COMMAND_LONG_ID)
|
||||
|
@ -36,7 +36,7 @@ function mavport:begin(_)
|
||||
self._rx_buf = nil
|
||||
self._rx_pos = 1
|
||||
|
||||
mavlink.init(1, 4) -- only one message we care about, don't need huge queue
|
||||
mavlink.init(4, 1) -- only one message we care about, don't need huge queue
|
||||
mavlink.register_rx_msgid(SERIAL_CONTROL.id) -- register it
|
||||
end
|
||||
|
||||
|
@ -8,8 +8,8 @@ local msg_map = {}
|
||||
local heartbeat_msgid = mavlink_msgs.get_msgid("HEARTBEAT")
|
||||
|
||||
msg_map[heartbeat_msgid] = "HEARTBEAT"
|
||||
-- initialise mavlink rx with number of messages, and buffer depth
|
||||
mavlink.init(1, 10)
|
||||
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
|
||||
mavlink.init(10, 1)
|
||||
-- register message id to receive
|
||||
mavlink.register_rx_msgid(heartbeat_msgid)
|
||||
local test_named_value = 0.0
|
||||
|
Loading…
Reference in New Issue
Block a user