RC_Channel: don't enter the config error loop on unknown options
... unless we are in SITL Users moving backwards and forwards between versions can hit this case too easily. We probably need a better story around this error loop so it's less confusing to the user about what's going on.
This commit is contained in:
parent
adc1d60ea5
commit
3fb596d5ae
@ -478,8 +478,10 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n",
|
||||
(unsigned)(this->ch_in+1), (unsigned)ch_option);
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
AP_BoardConfig::config_error("Failed to init: RC%u_OPTION: %u",
|
||||
(unsigned)(this->ch_in+1), (unsigned)ch_option);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user