|
|
|
@ -450,9 +450,9 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
@@ -450,9 +450,9 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
|
|
|
|
|
do_aux_function(ch_option, ch_flag); |
|
|
|
|
break; |
|
|
|
|
default: |
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialise RC function (%u)", ch_option); |
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialise RC function (%u)", (unsigned)ch_option); |
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
|
AP_HAL::panic("RC function (%u) initialisation not handled", ch_option); |
|
|
|
|
AP_HAL::panic("RC function (%u) initialisation not handled", (unsigned)ch_option); |
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|