diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp index ab8b6680cc..ee8f48e54f 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp @@ -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 ) { diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h index 22bed7f815..62f20ba256 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.h @@ -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;