mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
RC_Channel: add AUTOTUNE to init_aux_function routine
Also, cark it in SITL if we fail to initialise an aux function
This commit is contained in:
parent
53fbdc3750
commit
f2b1387c1c
@ -93,6 +93,7 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_
|
||||
case SAVE_WP:
|
||||
case RESETTOARMEDYAW:
|
||||
case AUTO:
|
||||
case AUTOTUNE:
|
||||
break;
|
||||
default:
|
||||
RC_Channel::init_aux_function(ch_option, ch_flag);
|
||||
|
@ -432,6 +432,9 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
|
||||
break;
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialise RC function (%u)", ch_option);
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
AP_HAL::panic("Initialisation failed");
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user