mirror of https://github.com/ArduPilot/ardupilot
Plane: move RST_SWITCH_CH to RCx_OPTION
This commit is contained in:
parent
2d91679ec2
commit
cca5e62c89
|
@ -638,12 +638,6 @@ const AP_Param::Info Plane::var_info[] = {
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
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
|
// @Param: TRIM_ARSPD_CM
|
||||||
// @DisplayName: Target airspeed
|
// @DisplayName: Target airspeed
|
||||||
// @Description: Target airspeed in cm/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
|
// @Description: Target airspeed in cm/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
|
||||||
|
|
|
@ -62,7 +62,7 @@ public:
|
||||||
k_param_flap_1_speed,
|
k_param_flap_1_speed,
|
||||||
k_param_flap_2_percent,
|
k_param_flap_2_percent,
|
||||||
k_param_flap_2_speed,
|
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_manual_level, // unused
|
||||||
k_param_land_pitch_cd, // unused - moved to AP_Landing
|
k_param_land_pitch_cd, // unused - moved to AP_Landing
|
||||||
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
|
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
|
||||||
|
@ -446,7 +446,6 @@ public:
|
||||||
AP_Int16 dspoiler_rud_rate;
|
AP_Int16 dspoiler_rud_rate;
|
||||||
AP_Int16 num_resets;
|
AP_Int16 num_resets;
|
||||||
AP_Int32 log_bitmask;
|
AP_Int32 log_bitmask;
|
||||||
AP_Int8 reset_switch_chan;
|
|
||||||
AP_Int32 RTL_altitude_cm;
|
AP_Int32 RTL_altitude_cm;
|
||||||
AP_Int16 pitch_trim_cd;
|
AP_Int16 pitch_trim_cd;
|
||||||
AP_Int16 FBWB_min_altitude_cm;
|
AP_Int16 FBWB_min_altitude_cm;
|
||||||
|
|
|
@ -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::FWD_THR:
|
||||||
case AUX_FUNC::LANDING_FLARE:
|
case AUX_FUNC::LANDING_FLARE:
|
||||||
case AUX_FUNC::PARACHUTE_RELEASE:
|
case AUX_FUNC::PARACHUTE_RELEASE:
|
||||||
|
case AUX_FUNC::MODE_SWITCH_RESET:
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::Q_ASSIST:
|
case AUX_FUNC::Q_ASSIST:
|
||||||
|
@ -319,6 +320,10 @@ case AUX_FUNC::ARSPD_CALIBRATE:
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case AUX_FUNC::MODE_SWITCH_RESET:
|
||||||
|
plane.reset_control_switch();
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
RC_Channel::do_aux_function(ch_option, ch_flag);
|
RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -251,25 +251,12 @@
|
||||||
# define AC_FENCE ENABLED
|
# define AC_FENCE ENABLED
|
||||||
#endif
|
#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
|
// a digital pin to set high when the geo-fence triggers. Defaults
|
||||||
// to -1, which means don't activate a pin
|
// to -1, which means don't activate a pin
|
||||||
#ifndef FENCE_TRIGGERED_PIN
|
#ifndef FENCE_TRIGGERED_PIN
|
||||||
# define FENCE_TRIGGERED_PIN -1
|
# define FENCE_TRIGGERED_PIN -1
|
||||||
#endif
|
#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
|
#ifndef HIL_SUPPORT
|
||||||
# define HIL_SUPPORT !HAL_MINIMIZE_FEATURES
|
# define HIL_SUPPORT !HAL_MINIMIZE_FEATURES
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -105,15 +105,7 @@ void Plane::read_control_switch()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// we look for changes in the switch position. If the
|
if (oldSwitchPosition != switchPosition) {
|
||||||
// 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 (switch_debouncer == false) {
|
if (switch_debouncer == false) {
|
||||||
// this ensures that mode switches only happen if the
|
// this ensures that mode switches only happen if the
|
||||||
|
|
Loading…
Reference in New Issue