Plane: increase NAV_SCRIPT timeout to 1s

this is needed for processing of very complex schedules
This commit is contained in:
Andrew Tridgell 2022-11-14 19:01:19 +11:00
parent 93353442a4
commit 21c9737ffa
1 changed files with 2 additions and 2 deletions

View File

@ -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");