mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Plane: added CHUTE_CHAN parameter for manual release
This commit is contained in:
parent
d20b86b95e
commit
5d1d54a8cb
@ -995,6 +995,12 @@ const AP_Param::Info Plane::var_info[] PROGMEM = {
|
|||||||
// @Group: CHUTE_
|
// @Group: CHUTE_
|
||||||
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
|
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
|
||||||
GOBJECT(parachute, "CHUTE_", AP_Parachute),
|
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
|
#endif
|
||||||
|
|
||||||
#if RANGEFINDER_ENABLED == ENABLED
|
#if RANGEFINDER_ENABLED == ENABLED
|
||||||
|
@ -144,9 +144,8 @@ public:
|
|||||||
k_param_rssi = 97,
|
k_param_rssi = 97,
|
||||||
k_param_rpm_sensor,
|
k_param_rpm_sensor,
|
||||||
k_param_parachute,
|
k_param_parachute,
|
||||||
|
|
||||||
// 100: Arming parameters
|
|
||||||
k_param_arming = 100,
|
k_param_arming = 100,
|
||||||
|
k_param_parachute_channel,
|
||||||
|
|
||||||
// 105: Extra parameters
|
// 105: Extra parameters
|
||||||
k_param_fence_retalt = 105,
|
k_param_fence_retalt = 105,
|
||||||
@ -490,6 +489,7 @@ public:
|
|||||||
AP_Int8 override_channel;
|
AP_Int8 override_channel;
|
||||||
#endif
|
#endif
|
||||||
AP_Int16 gcs_pid_mask;
|
AP_Int16 gcs_pid_mask;
|
||||||
|
AP_Int8 parachute_channel;
|
||||||
|
|
||||||
// RC channels
|
// RC channels
|
||||||
RC_Channel rc_1;
|
RC_Channel rc_1;
|
||||||
|
@ -60,6 +60,12 @@ void Plane::read_control_switch()
|
|||||||
inverted_flight = (control_mode != MANUAL && hal.rcin->read(g.inverted_flight_ch-1) > INVERTED_FLIGHT_PWM);
|
inverted_flight = (control_mode != MANUAL && hal.rcin->read(g.inverted_flight_ch-1) > INVERTED_FLIGHT_PWM);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (g.parachute_channel > 0) {
|
||||||
|
if (hal.rcin->read(g.parachute_channel-1) >= 1700) {
|
||||||
|
parachute_manual_release();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
if (g.override_channel > 0) {
|
if (g.override_channel > 0) {
|
||||||
// if the user has configured an override channel then check it
|
// if the user has configured an override channel then check it
|
||||||
|
Loading…
Reference in New Issue
Block a user