Plane: move RST_SWITCH_CH to RCx_OPTION

This commit is contained in:
Iampete1 2021-03-14 23:42:57 +00:00 committed by Andrew Tridgell
parent 2d91679ec2
commit cca5e62c89
5 changed files with 7 additions and 30 deletions

View File

@ -638,12 +638,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
// @Param: RST_SWITCH_CH
// @DisplayName: Reset Switch Channel
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
// @User: Advanced
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
// @Param: TRIM_ARSPD_CM
// @DisplayName: Target airspeed
// @Description: Target airspeed in cm/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.

View File

@ -62,7 +62,7 @@ public:
k_param_flap_1_speed,
k_param_flap_2_percent,
k_param_flap_2_speed,
k_param_reset_switch_chan,
k_param_reset_switch_chan, // unused - moved to RC option
k_param_manual_level, // unused
k_param_land_pitch_cd, // unused - moved to AP_Landing
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
@ -446,7 +446,6 @@ public:
AP_Int16 dspoiler_rud_rate;
AP_Int16 num_resets;
AP_Int32 log_bitmask;
AP_Int8 reset_switch_chan;
AP_Int32 RTL_altitude_cm;
AP_Int16 pitch_trim_cd;
AP_Int16 FBWB_min_altitude_cm;

View File

@ -160,6 +160,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
case AUX_FUNC::FWD_THR:
case AUX_FUNC::LANDING_FLARE:
case AUX_FUNC::PARACHUTE_RELEASE:
case AUX_FUNC::MODE_SWITCH_RESET:
break;
case AUX_FUNC::Q_ASSIST:
@ -319,6 +320,10 @@ case AUX_FUNC::ARSPD_CALIBRATE:
#endif
break;
case AUX_FUNC::MODE_SWITCH_RESET:
plane.reset_control_switch();
break;
default:
RC_Channel::do_aux_function(ch_option, ch_flag);
break;

View File

@ -251,25 +251,12 @@
# define AC_FENCE ENABLED
#endif
// pwm value on FENCE_CHANNEL to use to enable fenced mode
#ifndef FENCE_ENABLE_PWM
# define FENCE_ENABLE_PWM 1750
#endif
// a digital pin to set high when the geo-fence triggers. Defaults
// to -1, which means don't activate a pin
#ifndef FENCE_TRIGGERED_PIN
# define FENCE_TRIGGERED_PIN -1
#endif
// if RESET_SWITCH_CH is not zero, then this is the PWM value on
// that channel where we reset the control mode to the current switch
// position (to for example return to switched mode after failsafe or
// fence breach)
#ifndef RESET_SWITCH_CHAN_PWM
# define RESET_SWITCH_CHAN_PWM 1750
#endif
#ifndef HIL_SUPPORT
# define HIL_SUPPORT !HAL_MINIMIZE_FEATURES
#endif

View File

@ -105,15 +105,7 @@ void Plane::read_control_switch()
return;
}
// we look for changes in the switch position. If the
// RST_SWITCH_CH parameter is set, then it is a switch that can be
// used to force re-reading of the control switch. This is useful
// when returning to the previous mode after a failsafe or fence
// breach. This channel is best used on a momentary switch (such
// as a spring loaded trainer switch).
if (oldSwitchPosition != switchPosition ||
(g.reset_switch_chan != 0 &&
RC_Channels::get_radio_in(g.reset_switch_chan-1) > RESET_SWITCH_CHAN_PWM)) {
if (oldSwitchPosition != switchPosition) {
if (switch_debouncer == false) {
// this ensures that mode switches only happen if the