AP_Frsky_Telem: Add missing const in member functions

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2021-02-01 13:26:28 -03:00 committed by Andrew Tridgell
parent be37f10d61
commit aa55578008
2 changed files with 2 additions and 2 deletions

View File

@ -475,7 +475,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_batt(uint8_t instance)
* true if we need to respond to the last polling byte
* for FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
*/
bool AP_Frsky_SPort_Passthrough::is_passthrough_byte(const uint8_t byte)
bool AP_Frsky_SPort_Passthrough::is_passthrough_byte(const uint8_t byte) const
{
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
if( byte == _SPort_bidir.downlink1_sensor_id || byte == _SPort_bidir.downlink2_sensor_id ) {

View File

@ -146,7 +146,7 @@ private:
void send_sport_frame(uint8_t frame, uint16_t appid, uint32_t data);
// true if we need to respond to the last polling byte
bool is_passthrough_byte(const uint8_t byte);
bool is_passthrough_byte(const uint8_t byte) const;
uint8_t _paramID;