mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Scipting: cope with lua update being called too soon
in CI we occasionally get a loop called too fast (in one log the micros() timestamp step was zero)
This commit is contained in:
parent
4ab0919d63
commit
0d9397f451
@ -1819,6 +1819,11 @@ function do_path()
|
|||||||
local vel_length = ahrs_velned:length()
|
local vel_length = ahrs_velned:length()
|
||||||
|
|
||||||
local actual_dt = now - path_var.last_time
|
local actual_dt = now - path_var.last_time
|
||||||
|
if actual_dt < 0.25 / LOOP_RATE then
|
||||||
|
-- the update has been executed too soon
|
||||||
|
return true
|
||||||
|
end
|
||||||
|
|
||||||
path_var.last_time = now
|
path_var.last_time = now
|
||||||
|
|
||||||
local local_n_dt = actual_dt/path_var.total_time
|
local local_n_dt = actual_dt/path_var.total_time
|
||||||
|
Loading…
Reference in New Issue
Block a user