mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: fixed changing modes causing aerobatics abort
This commit is contained in:
parent
7fa45e343f
commit
a94f75fe29
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user