mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: Remove static from get_override_mask and make const
This commit is contained in:
parent
247a72b823
commit
2fff57708a
|
@ -479,7 +479,7 @@ public:
|
||||||
|
|
||||||
// returns a mask indicating which channels have overrides. Bit 0
|
// returns a mask indicating which channels have overrides. Bit 0
|
||||||
// is RC channel 1. Beware this is not a cheap call.
|
// is RC channel 1. Beware this is not a cheap call.
|
||||||
static uint16_t get_override_mask();
|
uint16_t get_override_mask() const;
|
||||||
|
|
||||||
class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option);
|
class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option);
|
||||||
bool duplicate_options_exist();
|
bool duplicate_options_exist();
|
||||||
|
|
|
@ -114,7 +114,7 @@ void RC_Channels::clear_overrides(void)
|
||||||
// copter and plane, RC_Channels needs to control failsafes to resolve this
|
// copter and plane, RC_Channels needs to control failsafes to resolve this
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t RC_Channels::get_override_mask(void)
|
uint16_t RC_Channels::get_override_mask(void) const
|
||||||
{
|
{
|
||||||
uint16_t ret = 0;
|
uint16_t ret = 0;
|
||||||
RC_Channels &_rc = rc();
|
RC_Channels &_rc = rc();
|
||||||
|
|
Loading…
Reference in New Issue