Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rc default for low and high #13975

Merged
merged 10 commits into from
Feb 10, 2021
2 changes: 1 addition & 1 deletion ArduPlane/control_modes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ void Plane::read_control_switch()

#if PARACHUTE == ENABLED
if (g.parachute_channel > 0) {
if (RC_Channels::get_radio_in(g.parachute_channel-1) >= 1700) {
if (RC_Channels::get_radio_in(g.parachute_channel-1) >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
parachute_manual_release();
}
}
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_fbwa.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ void ModeFBWA::update()
}
if (plane.g.fbwa_tdrag_chan > 0) {
// check for the user enabling FBWA taildrag takeoff mode
bool tdrag_mode = (RC_Channels::get_radio_in(plane.g.fbwa_tdrag_chan-1) > 1700);
bool tdrag_mode = (RC_Channels::get_radio_in(plane.g.fbwa_tdrag_chan-1) > RC_Channel::AUX_PWM_TRIGGER_HIGH);
if (tdrag_mode && !plane.auto_state.fbwa_tdrag_takeoff_mode) {
if (plane.auto_state.highest_airspeed < plane.g.takeoff_tdrag_speed1) {
plane.auto_state.fbwa_tdrag_takeoff_mode = true;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ void QuadPlane::tailsitter_output(void)

if (tailsitter.input_mask_chan > 0 &&
tailsitter.input_mask > 0 &&
RC_Channels::get_radio_in(tailsitter.input_mask_chan-1) > 1700) {
RC_Channels::get_radio_in(tailsitter.input_mask_chan-1) > RC_Channel::AUX_PWM_TRIGGER_HIGH) {
// the user is learning to prop-hang
if (tailsitter.input_mask & TAILSITTER_MASK_AILERON) {
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.channel_roll->get_control_in_zero_dz());
Expand Down
4 changes: 2 additions & 2 deletions Rover/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@ bool AP_Arming_Rover::rc_calibration_checks(const bool display_failure)
const RC_Channel *channel = channels[i];
const char *channel_name = channel_names[i];
// check if radio has been calibrated
if (channel->get_radio_min() > 1300) {
if (channel->get_radio_min() > RC_Channel::RC_CALIB_MIN_LIMIT_PWM) {
check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
return false;
}
if (channel->get_radio_max() < 1700) {
if (channel->get_radio_max() < RC_Channel::RC_CALIB_MAX_LIMIT_PWM) {
check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);
return false;
}
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1260,11 +1260,11 @@ bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channe
const RC_Channel *channel = channels[i];
const char *channel_name = channel_names[i];
// check if radio has been calibrated
if (channel->get_radio_min() > 1300) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There are two distinct uses of this pair of numbers (1300 and 1700).

One is setting strict endpoints for calibration values.

The other are a poor-man's RC_OPTION switch threshold values.

They should not be conflated.

if (channel->get_radio_min() > RC_Channel::RC_CALIB_MIN_LIMIT_PWM) {
check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
ret = false;
}
if (channel->get_radio_max() < 1700) {
if (channel->get_radio_max() < RC_Channel::RC_CALIB_MAX_LIMIT_PWM) {
check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);
ret = false;
}
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Button/AP_Button.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,12 +179,12 @@ void AP_Button::update(void)
// these values are the same as used in RC_Channel:
if (pwm_state & mask) {
// currently asserted; check to see if we should de-assert
if (pwm_us < RC_Channel::AUX_PWM_TRIGGER_LOW) {
if (pwm_us < RC_Channel::AUX_SWITCH_PWM_TRIGGER_LOW) {
new_pwm_state &= ~mask;
}
} else {
// currently not asserted; check to see if we should assert
if (pwm_us > RC_Channel::AUX_PWM_TRIGGER_HIGH) {
if (pwm_us > RC_Channel::AUX_SWITCH_PWM_TRIGGER_HIGH) {
new_pwm_state |= mask;
}
}
Expand Down
10 changes: 5 additions & 5 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,9 +180,9 @@ void AP_ICEngine::update(void)
// snap the input to either 1000, 1500, or 2000
// this is useful to compare a debounce changed value
// while ignoring tiny noise
if (cvalue >= 1700) {
if (cvalue >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
cvalue = 2000;
} else if ((cvalue > 800) && (cvalue <= 1300)) {
} else if ((cvalue > 800) && (cvalue <= RC_Channel::AUX_PWM_TRIGGER_LOW)) {
cvalue = 1300;
} else {
cvalue = 1500;
Expand All @@ -203,9 +203,9 @@ void AP_ICEngine::update(void)
}


if (state == ICE_OFF && start_chan_last_value >= 1700) {
if (state == ICE_OFF && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
should_run = true;
} else if (start_chan_last_value <= 1300) {
} else if (start_chan_last_value <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
should_run = false;
} else if (state != ICE_OFF) {
should_run = true;
Expand Down Expand Up @@ -360,7 +360,7 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he
if (c != nullptr && rc().has_valid_input()) {
// get starter control channel
uint16_t cvalue = c->get_radio_in();
if (cvalue >= start_chan_min_pwm && cvalue <= 1300) {
if (cvalue >= start_chan_min_pwm && cvalue <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
gcs().send_text(MAV_SEVERITY_INFO, "Engine: start control disabled");
return false;
}
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_OSD/AP_OSD_ParamScreen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -406,9 +406,9 @@ RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan)
// switch is reversed if 'reversed' option set on channel and switches reverse is allowed by RC_OPTIONS
bool switch_reversed = chan->get_reverse() && rc().switch_reverse_allowed();

if (in < 1300) {
if (in < RC_Channel::AUX_PWM_TRIGGER_LOW) {
return switch_reversed ? RC_Channel::AuxSwitchPos::HIGH : RC_Channel::AuxSwitchPos::LOW;
} else if (in > 1700) {
} else if (in > RC_Channel::AUX_PWM_TRIGGER_HIGH) {
return switch_reversed ? RC_Channel::AuxSwitchPos::LOW : RC_Channel::AuxSwitchPos::HIGH;
} else {
return RC_Channel::AuxSwitchPos::MIDDLE;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Tuning/AP_Tuning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ void AP_Tuning::check_selector_switch(void)
return;
}
uint16_t selector_in = selchan->get_radio_in();
if (selector_in >= 1700) {
if (selector_in >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
// high selector
if (selector_start_ms == 0) {
selector_start_ms = AP_HAL::millis();
Expand All @@ -90,7 +90,7 @@ void AP_Tuning::check_selector_switch(void)
changed = false;
need_revert = 0;
}
} else if (selector_in <= 1300) {
} else if (selector_in <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
// low selector
if (selector_start_ms != 0) {
uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
Expand Down
4 changes: 2 additions & 2 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
13 changes: 11 additions & 2 deletions libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -240,11 +240,20 @@ class RC_Channel {
#if !HAL_MINIMIZE_FEATURES
const char *string_for_aux_function(AUX_FUNC function) const;
#endif
// pwm value above which we condider that Radio min value is invalid
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

s/condider/consider/

static const uint16_t RC_CALIB_MIN_LIMIT_PWM = 1300;
// pwm value under which we condider that Radio max value is invalid
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

s/condider/consider/

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;
static const uint16_t AUX_PWM_TRIGGER_HIGH = 1700;
// pwm value below which the option will be disabled:
static const uint16_t AUX_PWM_TRIGGER_LOW = 1200;
static const uint16_t AUX_PWM_TRIGGER_LOW = 1300;

protected:

Expand Down