Skip to content

Commit

Permalink
RC_Channel: Aux switches to respect 'reverse' option
Browse files Browse the repository at this point in the history
  • Loading branch information
SergeyBokhantsev authored and tridge committed Jun 9, 2020
1 parent f04acbd commit f92d539
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 4 deletions.
8 changes: 6 additions & 2 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -966,10 +966,14 @@ bool RC_Channel::read_3pos_switch(RC_Channel::aux_switch_pos_t &ret) const
if (in <= 900 or in >= 2200) {
return false;
}

// 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) {
ret = LOW;
ret = switch_reversed ? HIGH : LOW;
} else if (in > AUX_PWM_TRIGGER_HIGH) {
ret = HIGH;
ret = switch_reversed ? LOW : HIGH;
} else {
ret = MIDDLE;
}
Expand Down
8 changes: 7 additions & 1 deletion libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -358,6 +358,11 @@ class RC_Channels {
return get_singleton() != nullptr && (_options & uint32_t(Option::FPORT_PAD));
}

// should a channel reverse option affect aux switches
bool switch_reverse_allowed(void) const {
return get_singleton() != nullptr && (_options & uint32_t(Option::ALLOW_SWITCH_REV));
}

bool ignore_overrides() const {
return _options & uint32_t(Option::IGNORE_OVERRIDES);
}
Expand All @@ -381,7 +386,7 @@ class RC_Channels {
float override_timeout_ms() const {
return _override_timeout.get() * 1e3f;
}

/*
get the RC input PWM value given a channel number. Note that
channel numbers start at 1, as this API is designed for use in
Expand All @@ -401,6 +406,7 @@ class RC_Channels {
LOG_DATA = (1 << 4), // log rc input bytes
ARMING_CHECK_THROTTLE = (1 << 5), // run an arming check for neutral throttle
ARMING_SKIP_CHECK_RPY = (1 << 6), // skip the an arming checks for the roll/pitch/yaw channels
ALLOW_SWITCH_REV = (1 << 7), // honor the reversed flag on switches
};

void new_override_received() {
Expand Down
2 changes: 1 addition & 1 deletion libraries/RC_Channel/RC_Channels_VarInfo.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = {
// @DisplayName: RC options
// @Description: RC input options
// @User: Advanced
// @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yay sticks
// @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yay sticks, 7:Allow Switch reverse
AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, 0),

AP_GROUPEND
Expand Down

0 comments on commit f92d539

Please sign in to comment.