ArduCopter: use AUX_FUNC instead of typedef aux_func_t

This commit is contained in:
Peter Barker 2024-02-14 13:36:11 +11:00 committed by Peter Barker
parent ad3724177d
commit d4708e2d52
4 changed files with 7 additions and 7 deletions

View File

@ -233,12 +233,12 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
// Inverted flight feature disabled for Heli Single and Dual frames
if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD &&
rc().find_channel_for_option(RC_Channel::aux_func_t::INVERTED) != nullptr) {
rc().find_channel_for_option(RC_Channel::AUX_FUNC::INVERTED) != nullptr) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Inverted flight option not supported");
return false;
}
// Ensure an Aux Channel is configured for motor interlock
if (rc().find_channel_for_option(RC_Channel::aux_func_t::MOTOR_INTERLOCK) == nullptr) {
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) == nullptr) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Motor Interlock not configured");
return false;
}

View File

@ -69,7 +69,7 @@ RC_Channel * RC_Channels_Copter::get_arming_channel(void) const
}
// init_aux_switch_function - initialize aux functions
void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
{
// init channel options
switch(ch_option) {
@ -156,7 +156,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
}
// do_aux_function - implement the function invoked by auxiliary switches
bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
{
switch(ch_option) {
case AUX_FUNC::FLIP:

View File

@ -11,8 +11,8 @@ public:
protected:
void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
private:

View File

@ -22,7 +22,7 @@ void Copter::tuning()
}
// exit immediately if a function is assigned to channel 6
if ((RC_Channel::aux_func_t)rc6->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING) {
if ((RC_Channel::AUX_FUNC)rc6->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING) {
return;
}