Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Correct compilation when AP_RSSI_ENABLED is false #25762

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions libraries/AP_Logger/LogFile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -248,6 +248,7 @@ void AP_Logger::Write_RCOUT(void)

}

#if AP_RSSI_ENABLED
// Write an RSSI packet
void AP_Logger::Write_RSSI()
{
Expand All @@ -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,
Expand Down
16 changes: 14 additions & 2 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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()
Expand Down Expand Up @@ -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();
Expand All @@ -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()
{
Expand Down