RC_Channel: require RC switch position transition for arming

currently if you turn your transmitter on at runtime we may try to arm the vehicle if your arming switches are asserted.

This patch changes things to we don't trust the first position seen from an RC receiver - we must see a transission for the arming options
This commit is contained in:
Peter Barker 2024-04-07 12:05:46 +10:00 committed by Peter Barker
parent 1ed388c2e6
commit 42c4329d4c
2 changed files with 34 additions and 0 deletions

View File

@ -624,6 +624,7 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
switch (ch_option) {
// the following functions do not need to be initialised:
case AUX_FUNC::ARMDISARM:
case AUX_FUNC::ARMDISARM_AIRMODE:
case AUX_FUNC::BATTERY_MPPT_ENABLE:
case AUX_FUNC::CAMERA_TRIGGER:
case AUX_FUNC::CLEAR_WP:
@ -828,6 +829,14 @@ bool RC_Channel::read_aux()
return false;
}
if (!switch_state.initialised) {
switch_state.initialised = true;
if (init_position_on_first_radio_read((AUX_FUNC)option.get())) {
switch_state.current_position = (int8_t)new_position;
switch_state.debounce_position = (int8_t)new_position;
}
}
if (!debounce_completed((int8_t)new_position)) {
return false;
}
@ -845,6 +854,23 @@ bool RC_Channel::read_aux()
return true;
}
// returns true if the first time we successfully read the
// channel's three-position-switch position we should record that
// position as the current position *without* executing the
// associated auxiliary function. e.g. do not attempt to arm a
// vehicle when the user turns on their transmitter with the arm
// switch high!
bool RC_Channel::init_position_on_first_radio_read(AUX_FUNC func) const
{
switch (func) {
case AUX_FUNC::ARMDISARM_AIRMODE:
case AUX_FUNC::ARMDISARM:
// we do not want to process
return true;
default:
return false;
}
}
void RC_Channel::do_aux_function_armdisarm(const AuxSwitchPos ch_flag)
{

View File

@ -407,11 +407,19 @@ private:
int8_t debounce_position = -1;
int8_t current_position = -1;
uint32_t last_edge_time_ms;
bool initialised;
} switch_state;
void reset_mode_switch();
void read_mode_switch();
bool debounce_completed(int8_t position);
// returns true if the first time we successfully read the
// channel's three-position-switch position we should record that
// position as the current position *without* executing the
// associated auxiliary function. e.g. do not attempt to arm a
// vehicle when the user turns on their transmitter with the arm
// switch high!
bool init_position_on_first_radio_read(AUX_FUNC func) const;
#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
// Structure to lookup switch change announcements