ArduPlane: return MAV_RESULT_FAILED from do_aux_function if invalid function

This commit is contained in:
Peter Barker 2021-02-24 20:48:16 +11:00 committed by Peter Barker
parent ce9800e597
commit cb8ca17035
2 changed files with 5 additions and 4 deletions

View File

@ -199,7 +199,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
}
// do_aux_function - implement the function invoked by auxillary switches
void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
{
switch(ch_option) {
case AUX_FUNC::INVERTED:
@ -325,7 +325,8 @@ case AUX_FUNC::ARSPD_CALIBRATE:
break;
default:
RC_Channel::do_aux_function(ch_option, ch_flag);
break;
return RC_Channel::do_aux_function(ch_option, ch_flag);
}
return true;
}

View File

@ -11,7 +11,7 @@ protected:
void init_aux_function(aux_func_t ch_option,
AuxSwitchPos ch_flag) override;
void do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
private: