From 9ebb87816a4d5f13abf592908679f265203464df Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 20 Dec 2024 22:24:53 +0000 Subject: [PATCH] RC_Channel: add source index to aux function trigger --- libraries/RC_Channel/RC_Channel.cpp | 21 ++++++++++++--------- libraries/RC_Channel/RC_Channel.h | 15 +++++++-------- 2 files changed, 19 insertions(+), 17 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 4feb512739..0663f4d0d7 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -779,7 +779,7 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos #endif #if AP_AHRS_ENABLED case AUX_FUNC::AHRS_TYPE: - run_aux_function(ch_option, ch_flag, AuxFuncTrigger::Source::INIT); + run_aux_function(ch_option, ch_flag, AuxFuncTrigger::Source::INIT, ch_in); break; #endif default: @@ -977,7 +977,7 @@ bool RC_Channel::read_aux() #endif // debounced; undertake the action: - run_aux_function(_option, new_position, AuxFuncTrigger::Source::RC, get_radio_in()); + run_aux_function(_option, new_position, AuxFuncTrigger::Source::RC, ch_in); return true; } @@ -1402,7 +1402,7 @@ void RC_Channel::do_aux_function_retract_mount(const AuxSwitchPos ch_flag, const } #endif // HAL_MOUNT_ENABLED -bool RC_Channel::run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTrigger::Source source, int16_t pwm) +bool RC_Channel::run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTrigger::Source source, uint16_t source_index) { #if AP_SCRIPTING_ENABLED rc().set_aux_cached(ch_option, pos); @@ -1412,7 +1412,7 @@ bool RC_Channel::run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncT func: ch_option, pos: pos, source: source, - pwm: pwm, + source_index: source_index, }; const bool ret = do_aux_function(trigger); @@ -1427,17 +1427,19 @@ bool RC_Channel::run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncT // @FieldValueEnum: pos: RC_Channel::AuxSwitchPos // @Field: source: source of auxiliary function invocation // @FieldValueEnum: source: RC_Channel::AuxFuncTrigger::Source + // @Field: index: index within source. 0 indexed. Invalid for scripting. // @Field: result: true if function was successful AP::logger().Write( "AUXF", - "TimeUS,function,pos,source,result", - "s#---", - "F----", - "QHBBB", + "TimeUS,function,pos,source,index,result", + "s#----", + "F-----", + "QHBBHB", AP_HAL::micros64(), uint16_t(ch_option), uint8_t(pos), uint8_t(source), + source_index, uint8_t(ret) ); #endif @@ -1915,7 +1917,8 @@ void RC_Channel::init_aux() if (!read_3pos_switch(position)) { position = AuxSwitchPos::LOW; } - init_aux_function((AUX_FUNC)option.get(), position); + + run_aux_function((AUX_FUNC)option.get(), position, AuxFuncTrigger::Source::INIT, ch_in); } // read_3pos_switch diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 670810add8..f0c5560e2f 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -326,14 +326,14 @@ public: MISSION, SCRIPTING, } source; - // Trigger PWM, only valid for RC source - int16_t pwm; + // Index within source + uint16_t source_index; }; AuxSwitchPos get_aux_switch_pos() const; // wrapper function around do_aux_function which allows us to log - bool run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTrigger::Source source, int16_t pwm = 0); + bool run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTrigger::Source source, uint16_t source_index); #if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED const char *string_for_aux_function(AUX_FUNC function) const; @@ -395,6 +395,8 @@ protected: // no action by default (e.g. Tracker, Sub, who do their own thing) }; + // the input channel this corresponds to + uint8_t ch_in; private: @@ -414,9 +416,6 @@ private: ControlType type_in; int16_t high_in; - // the input channel this corresponds to - uint8_t ch_in; - // overrides uint16_t override_value; uint32_t last_override_time; @@ -604,8 +603,8 @@ public: // method for other parts of the system (e.g. Button and mavlink) // to trigger auxiliary functions - bool run_aux_function(RC_Channel::AUX_FUNC ch_option, RC_Channel::AuxSwitchPos pos, RC_Channel::AuxFuncTrigger::Source source) { - return rc_channel(0)->run_aux_function(ch_option, pos, source); + bool run_aux_function(RC_Channel::AUX_FUNC ch_option, RC_Channel::AuxSwitchPos pos, RC_Channel::AuxFuncTrigger::Source source, uint16_t source_index) { + return rc_channel(0)->run_aux_function(ch_option, pos, source, source_index); } // check if flight mode channel is assigned RC option