mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: add const in member functions
This commit is contained in:
parent
14719826c8
commit
7c939c5c00
|
@ -513,7 +513,7 @@ public:
|
||||||
|
|
||||||
// check if flight mode channel is assigned RC option
|
// check if flight mode channel is assigned RC option
|
||||||
// return true if assigned
|
// 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
|
// flight_mode_channel_number must be overridden in vehicle specific code
|
||||||
virtual int8_t flight_mode_channel_number() const = 0;
|
virtual int8_t flight_mode_channel_number() const = 0;
|
||||||
|
@ -549,7 +549,7 @@ private:
|
||||||
AP_Int32 _options;
|
AP_Int32 _options;
|
||||||
AP_Int32 _protocols;
|
AP_Int32 _protocols;
|
||||||
|
|
||||||
RC_Channel *flight_mode_channel();
|
RC_Channel *flight_mode_channel() const;
|
||||||
|
|
||||||
// Allow override by default at start
|
// Allow override by default at start
|
||||||
bool _gcs_overrides_enabled = true;
|
bool _gcs_overrides_enabled = true;
|
||||||
|
|
|
@ -183,7 +183,7 @@ void RC_Channels::init_aux_all()
|
||||||
//
|
//
|
||||||
// Support for mode switches
|
// 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();
|
const int8_t num = flight_mode_channel_number();
|
||||||
if (num <= 0) {
|
if (num <= 0) {
|
||||||
|
@ -192,7 +192,7 @@ RC_Channel *RC_Channels::flight_mode_channel()
|
||||||
if (num >= NUM_RC_CHANNELS) {
|
if (num >= NUM_RC_CHANNELS) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
return channel(num-1);
|
return rc_channel(num-1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void RC_Channels::reset_mode_switch()
|
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
|
// check if flight mode channel is assigned RC option
|
||||||
// return true if assigned
|
// 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();
|
RC_Channel *chan = flight_mode_channel();
|
||||||
if (chan == nullptr) {
|
if (chan == nullptr) {
|
||||||
|
|
Loading…
Reference in New Issue