mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
RC_Channel: enter config_error loop for invalid RC option
This commit is contained in:
parent
9cf708b846
commit
285901f57c
@ -476,11 +476,10 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
|
|||||||
do_aux_function(ch_option, ch_flag);
|
do_aux_function(ch_option, ch_flag);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialise RC function (%u)", (unsigned)ch_option);
|
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n",
|
||||||
char errorMsg[51];
|
(unsigned)(this->ch_in+1), (unsigned)ch_option);
|
||||||
hal.util->snprintf(errorMsg, sizeof(errorMsg), "Failed to initialise RC function %u for channel %u",
|
AP_BoardConfig::config_error("Failed to init: RC%u_OPTION: %u",
|
||||||
(unsigned)ch_option, (unsigned)(this->ch_in+1));
|
(unsigned)(this->ch_in+1), (unsigned)ch_option);
|
||||||
AP_BoardConfig::rc_option_error(errorMsg);
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user