Skip to content

Commit 43ca87c

Browse files
committed
AP_Scripting: update so mavlink init intent matches behavior
RX message ID buffer sizes have been shrunk to the amount actually used.
1 parent fe3f12d commit 43ca87c

File tree

8 files changed

+13
-15
lines changed

8 files changed

+13
-15
lines changed

libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua

+2-2
Original file line numberDiff line numberDiff line change
@@ -2309,8 +2309,8 @@ local function mavlink_receiver()
23092309

23102310
msg_map[NAMED_VALUE_FLOAT_msgid] = "NAMED_VALUE_FLOAT"
23112311

2312-
-- initialise mavlink rx with number of messages, and buffer depth
2313-
mavlink.init(1, 10)
2312+
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
2313+
mavlink.init(10, 1)
23142314

23152315
-- register message id to receive
23162316
mavlink.register_rx_msgid(NAMED_VALUE_FLOAT_msgid)

libraries/AP_Scripting/applets/copter-slung-payload.lua

+2-2
Original file line numberDiff line numberDiff line change
@@ -103,8 +103,8 @@ local GLOBAL_POSITION_INT_ID = 33
103103
local msg_map = {}
104104
msg_map[GLOBAL_POSITION_INT_ID] = "GLOBAL_POSITION_INT"
105105

106-
-- initialize MAVLink rx with number of messages, and buffer depth
107-
mavlink:init(2, 5)
106+
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
107+
mavlink:init(5, 1)
108108

109109
-- register message id to receive
110110
mavlink:register_rx_msgid(GLOBAL_POSITION_INT_ID)

libraries/AP_Scripting/applets/follow-target-send.lua

+1-2
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,7 @@ local FOLT_ENABLE = bind_add_param("ENABLE", 1, 1)
4343
--]]
4444
local FOLT_MAV_CHAN = bind_add_param("MAV_CHAN", 2, 0)
4545

46-
-- initialize MAVLink rx with number of messages, and buffer depth
47-
mavlink:init(2, 5)
46+
-- mavlink:init(0, 0) -- we never receive, no need to init rx
4847

4948
-- send FOLLOW_TARGET message
5049
local function send_follow_target_msg()

libraries/AP_Scripting/applets/mount-poi.lua

+1-2
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,7 @@ local last_roi_switch_pos = 0 -- last known rc roi switch position. U
5151
local success_count = 0 -- count of the number of POI calculations (sent to GCS in CAMERA_FEEDBACK message)
5252

5353
-- mavlink message definition
54-
-- initialise mavlink rx with number of messages, and buffer depth
55-
mavlink.init(1, 10)
54+
-- mavlink.init(0, 0) -- we never receive, no need to init rx
5655
local messages = {}
5756
messages[180] = { -- CAMERA_FEEDBACK
5857
{ "time_usec", "<I8" },

libraries/AP_Scripting/examples/BQ40Z_bms_shutdown.lua

+2-2
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,8 @@ local MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246
3030
local MAV_RESULT_ACCEPTED = 0
3131
local MAV_RESULT_FAILED = 4
3232

33-
-- Initialize MAVLink rx with number of messages, and buffer depth
34-
mavlink:init(1, 10)
33+
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
34+
mavlink:init(10, 1)
3535
-- Register message id to receive
3636
mavlink:register_rx_msgid(COMMAND_LONG_ID)
3737
-- Block MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN so we can handle the ACK

libraries/AP_Scripting/examples/MAVLink_Commands.lua

+2-2
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,8 @@ local msg_map = {}
99
msg_map[COMMAND_ACK_ID] = "COMMAND_ACK"
1010
msg_map[COMMAND_LONG_ID] = "COMMAND_LONG"
1111

12-
-- initialize MAVLink rx with number of messages, and buffer depth
13-
mavlink:init(1, 10)
12+
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
13+
mavlink:init(10, 1)
1414

1515
-- register message id to receive
1616
mavlink:register_rx_msgid(COMMAND_LONG_ID)

libraries/AP_Scripting/modules/mavport.lua

+1-1
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ function mavport:begin(_)
3636
self._rx_buf = nil
3737
self._rx_pos = 1
3838

39-
mavlink.init(1, 4) -- only one message we care about, don't need huge queue
39+
mavlink.init(4, 1) -- only one message we care about, don't need huge queue
4040
mavlink.register_rx_msgid(SERIAL_CONTROL.id) -- register it
4141
end
4242

libraries/AP_Scripting/tests/mavlink_test.lua

+2-2
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,8 @@ local msg_map = {}
88
local heartbeat_msgid = mavlink_msgs.get_msgid("HEARTBEAT")
99

1010
msg_map[heartbeat_msgid] = "HEARTBEAT"
11-
-- initialise mavlink rx with number of messages, and buffer depth
12-
mavlink.init(1, 10)
11+
-- initialize MAVLink rx with buffer depth and number of rx message IDs to register
12+
mavlink.init(10, 1)
1313
-- register message id to receive
1414
mavlink.register_rx_msgid(heartbeat_msgid)
1515
local test_named_value = 0.0

0 commit comments

Comments
 (0)