Rover: fix nav_script_time timeout
This commit is contained in:
parent
df5c3acdfe
commit
020262bfe7
@ -882,7 +882,8 @@ bool ModeAuto::verify_nav_script_time()
|
|||||||
{
|
{
|
||||||
// if done or timeout then return true
|
// if done or timeout then return true
|
||||||
if (nav_scripting.done ||
|
if (nav_scripting.done ||
|
||||||
(AP_HAL::millis() - nav_scripting.start_ms) > (nav_scripting.timeout_s * 1000)) {
|
((nav_scripting.timeout_s > 0) &&
|
||||||
|
(AP_HAL::millis() - nav_scripting.start_ms) > (nav_scripting.timeout_s * 1000))) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user