Copter: do not use out-of-range aux switch values

This protects against FrSky SBUS that can send 874 for some channels even after recovering from a failsafe
This commit is contained in:
Randy Mackay 2019-01-10 11:33:21 +09:00
parent 32d0137c08
commit d11caf042d
2 changed files with 48 additions and 24 deletions

View File

@ -899,7 +899,7 @@ private:
bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check); bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check);
bool check_duplicate_auxsw(void); bool check_duplicate_auxsw(void);
void reset_control_switch(); void reset_control_switch();
uint8_t read_3pos_switch(uint8_t chan); bool read_3pos_switch(uint8_t chan, uint8_t &ret) const WARN_IF_UNUSED;
void read_aux_switches(); void read_aux_switches();
void init_aux_switches(); void init_aux_switches();
void init_aux_switch_function(int8_t ch_option, uint8_t ch_flag); void init_aux_switch_function(int8_t ch_option, uint8_t ch_flag);

View File

@ -4,13 +4,13 @@
//Documentation of Aux Switch Flags: //Documentation of Aux Switch Flags:
struct { struct {
uint8_t CH6_flag : 2; // 0, 1 // ch6 aux switch : 0 is low or false, 1 is center or true, 2 is high uint8_t CH6_flag; // ch6 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH7_flag : 2; // 2, 3 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high uint8_t CH7_flag; // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH8_flag : 2; // 4, 5 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high uint8_t CH8_flag; // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH9_flag : 2; // 6, 7 // ch9 aux switch : 0 is low or false, 1 is center or true, 2 is high uint8_t CH9_flag; // ch9 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH10_flag : 2; // 8, 9 // ch10 aux switch : 0 is low or false, 1 is center or true, 2 is high uint8_t CH10_flag; // ch10 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH11_flag : 2; // 10,11 // ch11 aux switch : 0 is low or false, 1 is center or true, 2 is high uint8_t CH11_flag; // ch11 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH12_flag : 2; // 12,13 // ch12 aux switch : 0 is low or false, 1 is center or true, 2 is high uint8_t CH12_flag; // ch12 aux switch : 0 is low or false, 1 is center or true, 2 is high
} aux_con; } aux_con;
void Copter::read_control_switch() void Copter::read_control_switch()
@ -113,21 +113,33 @@ void Copter::reset_control_switch()
} }
// read_3pos_switch // read_3pos_switch
uint8_t Copter::read_3pos_switch(uint8_t chan) bool Copter::read_3pos_switch(uint8_t chan, uint8_t &ret) const
{ {
uint16_t radio_in = RC_Channels::rc_channel(chan)->get_radio_in(); const uint16_t radio_in = RC_Channels::rc_channel(chan)->get_radio_in();
if (radio_in < AUX_SWITCH_PWM_TRIGGER_LOW) return AUX_SWITCH_LOW; // switch is in low position if ((radio_in <= 900) || (radio_in >= 2200)) {
if (radio_in > AUX_SWITCH_PWM_TRIGGER_HIGH) return AUX_SWITCH_HIGH; // switch is in high position return false;
return AUX_SWITCH_MIDDLE; // switch is in middle position }
if (radio_in < AUX_SWITCH_PWM_TRIGGER_LOW) {
// switch is in low position
ret = AUX_SWITCH_LOW;
} else if (radio_in > AUX_SWITCH_PWM_TRIGGER_HIGH) {
// switch is in high position
ret = AUX_SWITCH_HIGH;
} else {
// switch is in middle position
ret = AUX_SWITCH_MIDDLE;
}
return true;
} }
// can't take reference to a bitfield member, thus a #define: // can't take reference to a bitfield member, thus a #define:
#define read_aux_switch(chan, flag, option) \ #define read_aux_switch(chan, flag, option) \
do { \ do { \
switch_position = read_3pos_switch(chan); \ if (read_3pos_switch(chan, switch_position)) { \
if (debounce_aux_switch(chan, flag) && flag != switch_position) { \ if (debounce_aux_switch(chan, flag) && flag != switch_position) { \
flag = switch_position; \ flag = switch_position; \
do_aux_switch_function(option, flag); \ do_aux_switch_function(option, flag); \
} \
} \ } \
} while (false) } while (false)
@ -155,14 +167,26 @@ void Copter::read_aux_switches()
void Copter::init_aux_switches() void Copter::init_aux_switches()
{ {
// set the CH7 ~ CH12 flags // set the CH7 ~ CH12 flags
aux_con.CH7_flag = read_3pos_switch(CH_7); if (!read_3pos_switch(CH_7, aux_con.CH7_flag)) {
aux_con.CH8_flag = read_3pos_switch(CH_8); aux_con.CH7_flag = AUX_SWITCH_LOW;
aux_con.CH10_flag = read_3pos_switch(CH_10); }
aux_con.CH11_flag = read_3pos_switch(CH_11); if (!read_3pos_switch(CH_8, aux_con.CH8_flag)) {
aux_con.CH8_flag = AUX_SWITCH_LOW;
}
if (!read_3pos_switch(CH_10, aux_con.CH10_flag)) {
aux_con.CH10_flag = AUX_SWITCH_LOW;
}
if (!read_3pos_switch(CH_11, aux_con.CH11_flag)) {
aux_con.CH11_flag = AUX_SWITCH_LOW;
}
// ch9, ch12 only supported on some boards // ch9, ch12 only supported on some boards
aux_con.CH9_flag = read_3pos_switch(CH_9); if (!read_3pos_switch(CH_9, aux_con.CH9_flag)) {
aux_con.CH12_flag = read_3pos_switch(CH_12); aux_con.CH9_flag = AUX_SWITCH_LOW;
}
if (!read_3pos_switch(CH_12, aux_con.CH12_flag)) {
aux_con.CH12_flag = AUX_SWITCH_LOW;
}
// initialise functions assigned to switches // initialise functions assigned to switches
init_aux_switch_function(g.ch7_option, aux_con.CH7_flag); init_aux_switch_function(g.ch7_option, aux_con.CH7_flag);