diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 0666943e94b87..e4d3f1ff895b7 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -248,6 +248,7 @@ void AP_Logger::Write_RCOUT(void) } +#if AP_RSSI_ENABLED // Write an RSSI packet void AP_Logger::Write_RSSI() { @@ -264,6 +265,7 @@ void AP_Logger::Write_RSSI() }; WriteBlock(&pkt, sizeof(pkt)); } +#endif void AP_Logger::Write_Command(const mavlink_command_int_t &packet, uint8_t source_system, diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a81f3d5a38cb7..48c95b917f661 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1993,7 +1993,12 @@ void GCS_MAVLINK::send_rc_channels() const values[15], values[16], values[17], - receiver_rssi()); +#if AP_RSSI_ENABLED + receiver_rssi() +#else + 255 // meaning "unknown" +#endif + ); } bool GCS_MAVLINK::sending_mavlink1() const @@ -2024,7 +2029,12 @@ void GCS_MAVLINK::send_rc_channels_raw() const values[5], values[6], values[7], - receiver_rssi()); +#if AP_RSSI_ENABLED + receiver_rssi() +#else + 255 // meaning "unknown" +#endif +); } void GCS_MAVLINK::send_raw_imu() @@ -6637,6 +6647,7 @@ void GCS_MAVLINK::handle_manual_control(const mavlink_message_t &msg) } +#if AP_RSSI_ENABLED uint8_t GCS_MAVLINK::receiver_rssi() const { AP_RSSI *aprssi = AP::rssi(); @@ -6651,6 +6662,7 @@ uint8_t GCS_MAVLINK::receiver_rssi() const // scale across the full valid range return aprssi->read_receiver_rssi() * 254; } +#endif GCS &gcs() {