RC_Channel: add const in member functions

This commit is contained in:
Tatsuya Yamaguchi 2021-06-22 13:13:51 +09:00 committed by Andrew Tridgell
parent 14719826c8
commit 7c939c5c00
2 changed files with 5 additions and 5 deletions

View File

@ -513,7 +513,7 @@ public:
// check if flight mode channel is assigned RC option
// return true if assigned
bool flight_mode_channel_conflicts_with_rc_option();
bool flight_mode_channel_conflicts_with_rc_option() const;
// flight_mode_channel_number must be overridden in vehicle specific code
virtual int8_t flight_mode_channel_number() const = 0;
@ -549,7 +549,7 @@ private:
AP_Int32 _options;
AP_Int32 _protocols;
RC_Channel *flight_mode_channel();
RC_Channel *flight_mode_channel() const;
// Allow override by default at start
bool _gcs_overrides_enabled = true;

View File

@ -183,7 +183,7 @@ void RC_Channels::init_aux_all()
//
// Support for mode switches
//
RC_Channel *RC_Channels::flight_mode_channel()
RC_Channel *RC_Channels::flight_mode_channel() const
{
const int8_t num = flight_mode_channel_number();
if (num <= 0) {
@ -192,7 +192,7 @@ RC_Channel *RC_Channels::flight_mode_channel()
if (num >= NUM_RC_CHANNELS) {
return nullptr;
}
return channel(num-1);
return rc_channel(num-1);
}
void RC_Channels::reset_mode_switch()
@ -219,7 +219,7 @@ void RC_Channels::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()
bool RC_Channels::flight_mode_channel_conflicts_with_rc_option() const
{
RC_Channel *chan = flight_mode_channel();
if (chan == nullptr) {