Plane: move guided throttle passthrough to mode_guided

This commit is contained in:
Iampete1 2024-01-30 23:47:57 +00:00 committed by Andrew Tridgell
parent 98c59129ec
commit b119a2a6d7
2 changed files with 10 additions and 6 deletions

View File

@ -82,13 +82,21 @@ void ModeGuided::update()
plane.calc_nav_pitch(); plane.calc_nav_pitch();
} }
// Received an external msg that guides throttle in the last 3 seconds? // Throttle output
if (plane.aparm.throttle_cruise > 1 && if (plane.guided_throttle_passthru) {
// manual passthrough of throttle in fence breach
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.get_throttle_input(true));
} else if (plane.aparm.throttle_cruise > 1 &&
plane.guided_state.last_forced_throttle_ms > 0 && plane.guided_state.last_forced_throttle_ms > 0 &&
millis() - plane.guided_state.last_forced_throttle_ms < 3000) { millis() - plane.guided_state.last_forced_throttle_ms < 3000) {
// Received an external msg that guides throttle in the last 3 seconds?
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.guided_state.forced_throttle); SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.guided_state.forced_throttle);
} else { } else {
// TECS control
plane.calc_throttle(); plane.calc_throttle();
} }
} }

View File

@ -601,10 +601,6 @@ void Plane::set_throttle(void)
// get throttle, but adjust center to output TRIM_THROTTLE if flight option set // get throttle, but adjust center to output TRIM_THROTTLE if flight option set
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_adjusted_throttle_input(true)); SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_adjusted_throttle_input(true));
} }
} else if (control_mode->is_guided_mode() &&
guided_throttle_passthru) {
// manual pass through of throttle while in GUIDED
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true));
} }
if (control_mode->use_battery_compensation()) { if (control_mode->use_battery_compensation()) {