mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RCProtocol: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
a902c1d54b
commit
8f96580e9d
@ -45,7 +45,7 @@ public:
|
||||
NONE //last enum always is None
|
||||
};
|
||||
void init();
|
||||
bool valid_serial_prot()
|
||||
bool valid_serial_prot() const
|
||||
{
|
||||
return _valid_serial_prot;
|
||||
}
|
||||
|
@ -37,7 +37,7 @@ bool AP_RCProtocol_Backend::new_input()
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t AP_RCProtocol_Backend::num_channels()
|
||||
uint8_t AP_RCProtocol_Backend::num_channels() const
|
||||
{
|
||||
return _num_channels;
|
||||
}
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
uint16_t read(uint8_t chan);
|
||||
void read(uint16_t *pwm, uint8_t n);
|
||||
bool new_input();
|
||||
uint8_t num_channels();
|
||||
uint8_t num_channels() const;
|
||||
|
||||
// support for receivers that have FC initiated bind support
|
||||
virtual void start_bind(void) {}
|
||||
|
Loading…
Reference in New Issue
Block a user