mirror of https://github.com/ArduPilot/ardupilot
Plane: move CHUTE_CHAN to RC Options
This commit is contained in:
parent
eeab196d91
commit
5f555e5314
|
@ -816,12 +816,6 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
// @Group: CHUTE_
|
||||
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
|
||||
GOBJECT(parachute, "CHUTE_", AP_Parachute),
|
||||
|
||||
// @Param: CHUTE_CHAN
|
||||
// @DisplayName: Parachute release channel
|
||||
// @Description: If set to a non-zero value then this is an RC input channel number to use for manually releasing the parachute. When this channel goes above 1700 the parachute will be released
|
||||
// @User: Advanced
|
||||
GSCALAR(parachute_channel, "CHUTE_CHAN", 0),
|
||||
#endif
|
||||
|
||||
// @Group: RNGFND
|
||||
|
|
|
@ -142,7 +142,7 @@ public:
|
|||
k_param_rpm_sensor,
|
||||
k_param_parachute,
|
||||
k_param_arming = 100,
|
||||
k_param_parachute_channel,
|
||||
k_param_parachute_channel, // unused - moved to RC option
|
||||
k_param_crash_accel_threshold,
|
||||
k_param_override_safety,
|
||||
k_param_land_throttle_slewrate, // 104 unused - moved to AP_Landing
|
||||
|
@ -484,7 +484,6 @@ public:
|
|||
AP_Int8 override_safety;
|
||||
#endif
|
||||
AP_Int16 gcs_pid_mask;
|
||||
AP_Int8 parachute_channel;
|
||||
};
|
||||
|
||||
/*
|
||||
|
|
|
@ -158,6 +158,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
|||
case AUX_FUNC::FBWA:
|
||||
case AUX_FUNC::FWD_THR:
|
||||
case AUX_FUNC::LANDING_FLARE:
|
||||
case AUX_FUNC::PARACHUTE_RELEASE:
|
||||
break;
|
||||
|
||||
case AUX_FUNC::Q_ASSIST:
|
||||
|
@ -310,6 +311,12 @@ case AUX_FUNC::ARSPD_CALIBRATE:
|
|||
do_aux_function_flare(ch_flag);
|
||||
break;
|
||||
|
||||
case AUX_FUNC::PARACHUTE_RELEASE:
|
||||
#if PARACHUTE == ENABLED
|
||||
plane.parachute_manual_release();
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||
break;
|
||||
|
|
|
@ -131,13 +131,6 @@ void Plane::read_control_switch()
|
|||
|
||||
switch_debouncer = false;
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
if (g.parachute_channel > 0) {
|
||||
if (RC_Channels::get_radio_in(g.parachute_channel-1) >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
parachute_manual_release();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t Plane::readSwitch(void) const
|
||||
|
|
Loading…
Reference in New Issue