mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: add AUX_SWITCH_PWM_TRIGGER_LOW and AUX_SWITCH_PWM_TRIGGER_HIGH
This commit is contained in:
parent
68a27e3b41
commit
0725cbdffc
|
@ -1156,9 +1156,9 @@ bool RC_Channel::read_3pos_switch(RC_Channel::AuxSwitchPos &ret) const
|
|||
// switch is reversed if 'reversed' option set on channel and switches reverse is allowed by RC_OPTIONS
|
||||
bool switch_reversed = reversed && rc().switch_reverse_allowed();
|
||||
|
||||
if (in < AUX_PWM_TRIGGER_LOW) {
|
||||
if (in < AUX_SWITCH_PWM_TRIGGER_LOW) {
|
||||
ret = switch_reversed ? AuxSwitchPos::HIGH : AuxSwitchPos::LOW;
|
||||
} else if (in > AUX_PWM_TRIGGER_HIGH) {
|
||||
} else if (in > AUX_SWITCH_PWM_TRIGGER_HIGH) {
|
||||
ret = switch_reversed ? AuxSwitchPos::LOW : AuxSwitchPos::HIGH;
|
||||
} else {
|
||||
ret = AuxSwitchPos::MIDDLE;
|
||||
|
|
|
@ -245,6 +245,10 @@ public:
|
|||
// pwm value under which we condider that Radio max value is invalid
|
||||
static const uint16_t RC_CALIB_MAX_LIMIT_PWM = 1700;
|
||||
|
||||
// pwm value above which the switch/button will be invoked:
|
||||
static const uint16_t AUX_SWITCH_PWM_TRIGGER_HIGH = 1800;
|
||||
// pwm value below which the switch/button will be disabled:
|
||||
static const uint16_t AUX_SWITCH_PWM_TRIGGER_LOW = 1200;
|
||||
|
||||
// pwm value above which the option will be invoked:
|
||||
static const uint16_t AUX_PWM_TRIGGER_HIGH = 1800;
|
||||
|
|
Loading…
Reference in New Issue