RC_Channel: correct function initialisation
This commit is contained in:
parent
ac4a05ffbf
commit
ab444e1d26
@ -500,9 +500,9 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo
|
||||
case AUX_FUNC::SPRAYER:
|
||||
#if HAL_MOUNT_ENABLED
|
||||
case AUX_FUNC::RETRACT_MOUNT:
|
||||
#endif
|
||||
do_aux_function(ch_option, ch_flag);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n",
|
||||
(unsigned)(this->ch_in+1), (unsigned)ch_option);
|
||||
|
Loading…
Reference in New Issue
Block a user