From d1a1bcba19c47bf35e01efaa48e7d1b6a5f46d5a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Apr 2024 10:54:06 +1000 Subject: [PATCH] RC_Channel: process only transitions after rc is valid for arm_emergency_stop switch and parachute deploy switch --- libraries/RC_Channel/RC_Channel.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 1498a2f16a..04a96b0b5b 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -868,6 +868,9 @@ bool RC_Channel::init_position_on_first_radio_read(AUX_FUNC func) const switch (func) { case AUX_FUNC::ARMDISARM_AIRMODE: case AUX_FUNC::ARMDISARM: + case AUX_FUNC::ARM_EMERGENCY_STOP: + case AUX_FUNC::PARACHUTE_RELEASE: + // we do not want to process return true; default: @@ -1154,7 +1157,6 @@ void RC_Channel::do_aux_function_sprayer(const AuxSwitchPos ch_flag) if (sprayer == nullptr) { return; } - sprayer->run(ch_flag == AuxSwitchPos::HIGH); // if we are disarmed the pilot must want to test the pump sprayer->test_pump((ch_flag == AuxSwitchPos::HIGH) && !hal.util->get_soft_armed());