mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: fixed NaN in path lookahead at end of schedule
this can happen at high speedups under SITL
This commit is contained in:
parent
27261639d7
commit
ece61c29d5
@ -2717,9 +2717,11 @@ function do_path()
|
||||
lookahead_bf_dps:y(),
|
||||
path_rate_bf_dps:z(),
|
||||
lookahead_bf_dps:z())
|
||||
if not Vec3IsNaN(lookahead_bf_dps) then
|
||||
path_rate_bf_dps:y(lookahead_bf_dps:y())
|
||||
path_rate_bf_dps:z(lookahead_bf_dps:z())
|
||||
end
|
||||
end
|
||||
|
||||
--[[
|
||||
calculate an additional yaw rate to get us to the right angle of sideslip for knifeedge
|
||||
|
Loading…
Reference in New Issue
Block a user