Skip to content

Commit

Permalink
Plane: fixed throttle_at_zero()
Browse files Browse the repository at this point in the history
this fixes a bug with TVBS land flare handling. The if() statement was
just far too complex and was giving the wrong answer
  • Loading branch information
tridge committed Mar 14, 2024
1 parent 14b1237 commit b4a97ec
Showing 1 changed file with 9 additions and 5 deletions.
14 changes: 9 additions & 5 deletions ArduPlane/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -438,11 +438,15 @@ float Plane::rudder_in_expo(bool use_dz) const

bool Plane::throttle_at_zero(void) const
{
/* true if throttle stick is at idle position...if throttle trim has been moved
to center stick area in conjunction with sprung throttle, cannot use in_trim, must use rc_min
*/
if (((!(flight_option_enabled(FlightOptions::CENTER_THROTTLE_TRIM) && channel_throttle->in_trim_dz())) ||
(flight_option_enabled(FlightOptions::CENTER_THROTTLE_TRIM)&& channel_throttle->in_min_dz()))) {
/*
true if throttle stick is at idle position...if throttle trim has been moved
to center stick area in conjunction with sprung throttle, cannot use in_trim, must use rc_min
*/
const bool center_trim = flight_option_enabled(FlightOptions::CENTER_THROTTLE_TRIM);
if (center_trim && channel_throttle->in_trim_dz()) {
return true;
}
if (!center_trim && channel_throttle->in_min_dz()) {
return true;
}
return false;
Expand Down

0 comments on commit b4a97ec

Please sign in to comment.