mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: fixed throttle_at_zero()
this fixes a bug with TVBS land flare handling. The if() statement was just far too complex and was giving the wrong answer
This commit is contained in:
parent
4d1dd060f5
commit
dac11936ac
@ -438,11 +438,15 @@ float Plane::rudder_in_expo(bool use_dz) const
|
|||||||
|
|
||||||
bool Plane::throttle_at_zero(void) 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
|
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()))) {
|
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 true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user