mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: increase NAV_SCRIPT timeout to 1s
this is needed for processing of very complex schedules
This commit is contained in:
parent
93353442a4
commit
21c9737ffa
@ -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
|
// check if we are in a NAV_SCRIPT_* command
|
||||||
bool Plane::nav_scripting_active(void)
|
bool Plane::nav_scripting_active(void)
|
||||||
{
|
{
|
||||||
if (nav_scripting.enabled && AP_HAL::millis() - nav_scripting.current_ms > 200) {
|
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 200ms
|
// set_target_throttle_rate_rpy has not been called from script in last 1000ms
|
||||||
nav_scripting.enabled = false;
|
nav_scripting.enabled = false;
|
||||||
nav_scripting.current_ms = 0;
|
nav_scripting.current_ms = 0;
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "NavScript time out");
|
gcs().send_text(MAV_SEVERITY_INFO, "NavScript time out");
|
||||||
|
Loading…
Reference in New Issue
Block a user