Browse Source

Rover: fix nav_script_time timeout

gps-1.3.1
Randy Mackay 3 years ago
parent
commit
020262bfe7
  1. 3
      Rover/mode_auto.cpp

3
Rover/mode_auto.cpp

@ -882,7 +882,8 @@ bool ModeAuto::verify_nav_script_time() @@ -882,7 +882,8 @@ bool ModeAuto::verify_nav_script_time()
{
// if done or timeout then return true
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 false;

Loading…
Cancel
Save