mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: mount-djirs2: filter out ignored packets
Allows using a smaller buffer and simplifying the script logic.
This commit is contained in:
parent
afcc722995
commit
1f0dff0178
|
@ -151,7 +151,6 @@ local last_print_ms = uint32_t(0) -- system time that debug output was las
|
||||||
local bytes_read = 0 -- number of bytes read from gimbal
|
local bytes_read = 0 -- number of bytes read from gimbal
|
||||||
local bytes_written = 0 -- number of bytes written to gimbal
|
local bytes_written = 0 -- number of bytes written to gimbal
|
||||||
local bytes_error = 0 -- number of bytes read that could not be parsed
|
local bytes_error = 0 -- number of bytes read that could not be parsed
|
||||||
local msg_ignored = 0 -- number of ignored messages (because frame id does not match)
|
|
||||||
local write_fails = 0 -- number of times write failed
|
local write_fails = 0 -- number of times write failed
|
||||||
local execute_fails = 0 -- number of times that gimbal was unable to execute the command
|
local execute_fails = 0 -- number of times that gimbal was unable to execute the command
|
||||||
local reply_timeouts = 0 -- number of timeouts waiting for replies
|
local reply_timeouts = 0 -- number of timeouts waiting for replies
|
||||||
|
@ -344,9 +343,9 @@ function init()
|
||||||
do return end
|
do return end
|
||||||
end
|
end
|
||||||
|
|
||||||
-- get CAN device
|
-- get CAN device and filter to receive only replies from the gimbal
|
||||||
driver = CAN:get_device(25)
|
driver = CAN:get_device(8) -- buffer up to two replies
|
||||||
if driver then
|
if driver and driver:add_filter(-1, RECEIVE_FRAMEID) then
|
||||||
initialised = true
|
initialised = true
|
||||||
gcs:send_text(MAV_SEVERITY.INFO, "DJIR: mount driver started")
|
gcs:send_text(MAV_SEVERITY.INFO, "DJIR: mount driver started")
|
||||||
else
|
else
|
||||||
|
@ -560,18 +559,13 @@ end
|
||||||
-- consume incoming CAN packets
|
-- consume incoming CAN packets
|
||||||
function read_incoming_packets()
|
function read_incoming_packets()
|
||||||
local canframe
|
local canframe
|
||||||
repeat
|
while true do
|
||||||
canframe = driver:read_frame()
|
canframe = driver:read_frame()
|
||||||
if canframe then
|
if not canframe then return end
|
||||||
if uint32_t(canframe:id()) == uint32_t(RECEIVE_FRAMEID) then
|
for i = 0, canframe:dlc()-1 do
|
||||||
for i = 0, canframe:dlc()-1 do
|
parse_byte(canframe:data(i))
|
||||||
parse_byte(canframe:data(i))
|
|
||||||
end
|
|
||||||
else
|
|
||||||
msg_ignored = msg_ignored + 1
|
|
||||||
end
|
|
||||||
end
|
end
|
||||||
until not canframe
|
end
|
||||||
end
|
end
|
||||||
|
|
||||||
-- parse an byte from the gimbal
|
-- parse an byte from the gimbal
|
||||||
|
@ -742,12 +736,7 @@ function update()
|
||||||
-- report parsing status
|
-- report parsing status
|
||||||
if (DJIR_DEBUG:get() > 0) and ((now_ms - last_print_ms) > 5000) then
|
if (DJIR_DEBUG:get() > 0) and ((now_ms - last_print_ms) > 5000) then
|
||||||
last_print_ms = now_ms
|
last_print_ms = now_ms
|
||||||
gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: r:%u w:%u fail:%u,%u perr:%u to:%u ign:%u", bytes_read, bytes_written, write_fails, execute_fails, bytes_error, reply_timeouts, msg_ignored))
|
gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: r:%u w:%u fail:%u,%u perr:%u to:%u", bytes_read, bytes_written, write_fails, execute_fails, bytes_error, reply_timeouts))
|
||||||
end
|
|
||||||
|
|
||||||
-- do not send any messages until CAN traffic has been seen
|
|
||||||
if msg_ignored == 0 and bytes_read == 0 then
|
|
||||||
return update, UPDATE_INTERVAL_MS
|
|
||||||
end
|
end
|
||||||
|
|
||||||
-- handle expected reply timeouts
|
-- handle expected reply timeouts
|
||||||
|
|
Loading…
Reference in New Issue