mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: change or to ||
This commit is contained in:
parent
002b00f69d
commit
c17ef36354
|
@ -1195,7 +1195,7 @@ void RC_Channel::init_aux()
|
||||||
bool RC_Channel::read_3pos_switch(RC_Channel::AuxSwitchPos &ret) const
|
bool RC_Channel::read_3pos_switch(RC_Channel::AuxSwitchPos &ret) const
|
||||||
{
|
{
|
||||||
const uint16_t in = get_radio_in();
|
const uint16_t in = get_radio_in();
|
||||||
if (in <= RC_MIN_LIMIT_PWM or in >= RC_MAX_LIMIT_PWM) {
|
if (in <= RC_MIN_LIMIT_PWM || in >= RC_MAX_LIMIT_PWM) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue