diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 6f758539f6..bdadc98fbd 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -1190,8 +1190,8 @@ bool Plane::verify_nav_script_time(const AP_Mission::Mission_Command& cmd) // check if we are in a NAV_SCRIPT_* command bool Plane::nav_scripting_active(void) { - if (nav_scripting.enabled && AP_HAL::millis() - nav_scripting.current_ms > 200) { - // set_target_throttle_rate_rpy has not been called from script in last 200ms + if (nav_scripting.enabled && AP_HAL::millis() - nav_scripting.current_ms > 1000) { + // set_target_throttle_rate_rpy has not been called from script in last 1000ms nav_scripting.enabled = false; nav_scripting.current_ms = 0; gcs().send_text(MAV_SEVERITY_INFO, "NavScript time out");