From a94f75fe29749b3c6f250bdf6c5105d3387e4063 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 5 Nov 2022 14:24:02 +1100 Subject: [PATCH] Plane: fixed changing modes causing aerobatics abort --- ArduPlane/commands_logic.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index c8df864fa6..7e365b932f 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -1190,10 +1190,11 @@ 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 (AP_HAL::millis() - nav_scripting.current_ms > 200) { + 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 nav_scripting.enabled = false; nav_scripting.current_ms = 0; + gcs().send_text(MAV_SEVERITY_INFO, "NavScript time out"); } if (control_mode == &mode_auto && mission.get_current_nav_cmd().id != MAV_CMD_NAV_SCRIPT_TIME) { @@ -1235,7 +1236,6 @@ void Plane::set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps nav_scripting.yaw_rate_dps = constrain_float(yaw_rate_dps, -g.acro_yaw_rate, g.acro_yaw_rate); nav_scripting.throttle_pct = constrain_float(throttle_pct, aparm.throttle_min, aparm.throttle_max); nav_scripting.current_ms = AP_HAL::millis(); - nav_scripting.enabled = true; } // enable NAV_SCRIPTING takeover in modes other than AUTO using script time mission commands @@ -1252,6 +1252,7 @@ bool Plane::nav_scripting_enable(uint8_t mode) case Mode::Number::CRUISE: case Mode::Number::LOITER: nav_scripting.enabled = true; + nav_scripting.current_ms = AP_HAL::millis(); break; default: nav_scripting.enabled = false;