mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: add flight mode conflict check
This commit is contained in:
parent
d599052da3
commit
5a8ebeda1d
|
@ -511,6 +511,13 @@ public:
|
|||
return rc_channel(0)->run_aux_function(ch_option, pos, source);
|
||||
}
|
||||
|
||||
// check if flight mode channel is assigned RC option
|
||||
// return true if assigned
|
||||
bool flight_mode_channel_conflicts_with_rc_option();
|
||||
|
||||
// flight_mode_channel_number must be overridden in vehicle specific code
|
||||
virtual int8_t flight_mode_channel_number() const = 0;
|
||||
|
||||
protected:
|
||||
|
||||
enum class Option {
|
||||
|
@ -542,8 +549,6 @@ private:
|
|||
AP_Int32 _options;
|
||||
AP_Int32 _protocols;
|
||||
|
||||
// flight_mode_channel_number must be overridden in vehicle specific code
|
||||
virtual int8_t flight_mode_channel_number() const = 0;
|
||||
RC_Channel *flight_mode_channel();
|
||||
|
||||
// Allow override by default at start
|
||||
|
|
|
@ -217,6 +217,17 @@ void RC_Channels::read_mode_switch()
|
|||
c->read_mode_switch();
|
||||
}
|
||||
|
||||
// check if flight mode channel is assigned RC option
|
||||
// return true if assigned
|
||||
bool RC_Channels::flight_mode_channel_conflicts_with_rc_option()
|
||||
{
|
||||
RC_Channel *chan = flight_mode_channel();
|
||||
if (chan == nullptr) {
|
||||
return false;
|
||||
}
|
||||
return (RC_Channel::aux_func_t)chan->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING;
|
||||
}
|
||||
|
||||
/*
|
||||
get the RC input PWM value given a channel number. Note that
|
||||
channel numbers start at 1, as this API is designed for use in
|
||||
|
|
Loading…
Reference in New Issue