mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
ArduPlane: rename within_min_dz to in_min_dz for consistency
... consistency with in_trim_dz
This commit is contained in:
parent
30c08c1e7c
commit
302c8e4b98
@ -430,7 +430,7 @@ bool Plane::throttle_at_zero(void) const
|
|||||||
to center stick area in conjunction with sprung throttle, cannot use in_trim, must use rc_min
|
to center stick area in conjunction with sprung throttle, cannot use in_trim, must use rc_min
|
||||||
*/
|
*/
|
||||||
if (((!(g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM) && channel_throttle->in_trim_dz()) ||
|
if (((!(g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM) && channel_throttle->in_trim_dz()) ||
|
||||||
(g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM && channel_throttle->within_min_dz()))) {
|
(g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM && channel_throttle->in_min_dz()))) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user