mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
RC_Channel: add source index to aux function trigger
This commit is contained in:
parent
f5dee94a5d
commit
9ebb87816a
@ -779,7 +779,7 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
|
|||||||
#endif
|
#endif
|
||||||
#if AP_AHRS_ENABLED
|
#if AP_AHRS_ENABLED
|
||||||
case AUX_FUNC::AHRS_TYPE:
|
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;
|
break;
|
||||||
#endif
|
#endif
|
||||||
default:
|
default:
|
||||||
@ -977,7 +977,7 @@ bool RC_Channel::read_aux()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// debounced; undertake the action:
|
// 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;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1402,7 +1402,7 @@ void RC_Channel::do_aux_function_retract_mount(const AuxSwitchPos ch_flag, const
|
|||||||
}
|
}
|
||||||
#endif // HAL_MOUNT_ENABLED
|
#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
|
#if AP_SCRIPTING_ENABLED
|
||||||
rc().set_aux_cached(ch_option, pos);
|
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,
|
func: ch_option,
|
||||||
pos: pos,
|
pos: pos,
|
||||||
source: source,
|
source: source,
|
||||||
pwm: pwm,
|
source_index: source_index,
|
||||||
};
|
};
|
||||||
|
|
||||||
const bool ret = do_aux_function(trigger);
|
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
|
// @FieldValueEnum: pos: RC_Channel::AuxSwitchPos
|
||||||
// @Field: source: source of auxiliary function invocation
|
// @Field: source: source of auxiliary function invocation
|
||||||
// @FieldValueEnum: source: RC_Channel::AuxFuncTrigger::Source
|
// @FieldValueEnum: source: RC_Channel::AuxFuncTrigger::Source
|
||||||
|
// @Field: index: index within source. 0 indexed. Invalid for scripting.
|
||||||
// @Field: result: true if function was successful
|
// @Field: result: true if function was successful
|
||||||
AP::logger().Write(
|
AP::logger().Write(
|
||||||
"AUXF",
|
"AUXF",
|
||||||
"TimeUS,function,pos,source,result",
|
"TimeUS,function,pos,source,index,result",
|
||||||
"s#---",
|
"s#----",
|
||||||
"F----",
|
"F-----",
|
||||||
"QHBBB",
|
"QHBBHB",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
uint16_t(ch_option),
|
uint16_t(ch_option),
|
||||||
uint8_t(pos),
|
uint8_t(pos),
|
||||||
uint8_t(source),
|
uint8_t(source),
|
||||||
|
source_index,
|
||||||
uint8_t(ret)
|
uint8_t(ret)
|
||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
@ -1915,7 +1917,8 @@ void RC_Channel::init_aux()
|
|||||||
if (!read_3pos_switch(position)) {
|
if (!read_3pos_switch(position)) {
|
||||||
position = AuxSwitchPos::LOW;
|
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
|
// read_3pos_switch
|
||||||
|
@ -326,14 +326,14 @@ public:
|
|||||||
MISSION,
|
MISSION,
|
||||||
SCRIPTING,
|
SCRIPTING,
|
||||||
} source;
|
} source;
|
||||||
// Trigger PWM, only valid for RC source
|
// Index within source
|
||||||
int16_t pwm;
|
uint16_t source_index;
|
||||||
};
|
};
|
||||||
|
|
||||||
AuxSwitchPos get_aux_switch_pos() const;
|
AuxSwitchPos get_aux_switch_pos() const;
|
||||||
|
|
||||||
// wrapper function around do_aux_function which allows us to log
|
// 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
|
#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
|
||||||
const char *string_for_aux_function(AUX_FUNC function) const;
|
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)
|
// no action by default (e.g. Tracker, Sub, who do their own thing)
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// the input channel this corresponds to
|
||||||
|
uint8_t ch_in;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
@ -414,9 +416,6 @@ private:
|
|||||||
ControlType type_in;
|
ControlType type_in;
|
||||||
int16_t high_in;
|
int16_t high_in;
|
||||||
|
|
||||||
// the input channel this corresponds to
|
|
||||||
uint8_t ch_in;
|
|
||||||
|
|
||||||
// overrides
|
// overrides
|
||||||
uint16_t override_value;
|
uint16_t override_value;
|
||||||
uint32_t last_override_time;
|
uint32_t last_override_time;
|
||||||
@ -604,8 +603,8 @@ public:
|
|||||||
|
|
||||||
// method for other parts of the system (e.g. Button and mavlink)
|
// method for other parts of the system (e.g. Button and mavlink)
|
||||||
// to trigger auxiliary functions
|
// to trigger auxiliary functions
|
||||||
bool run_aux_function(RC_Channel::AUX_FUNC ch_option, RC_Channel::AuxSwitchPos pos, RC_Channel::AuxFuncTrigger::Source 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);
|
return rc_channel(0)->run_aux_function(ch_option, pos, source, source_index);
|
||||||
}
|
}
|
||||||
|
|
||||||
// check if flight mode channel is assigned RC option
|
// check if flight mode channel is assigned RC option
|
||||||
|
Loading…
Reference in New Issue
Block a user