mirror of https://github.com/ArduPilot/ardupilot
AP_MSP: add and use AP_RSSI_ENABLED
This commit is contained in:
parent
e95b1e5dd3
commit
03218b11ac
|
@ -1261,6 +1261,7 @@ bool AP_MSP_Telem_Backend::displaying_stats_screen() const
|
|||
|
||||
bool AP_MSP_Telem_Backend::get_rssi(float &rssi) const
|
||||
{
|
||||
#if AP_RSSI_ENABLED
|
||||
AP_RSSI* ap_rssi = AP::rssi();
|
||||
if (ap_rssi == nullptr) {
|
||||
return false;
|
||||
|
@ -1270,5 +1271,9 @@ bool AP_MSP_Telem_Backend::get_rssi(float &rssi) const
|
|||
}
|
||||
rssi = ap_rssi->read_receiver_rssi(); // range is [0-1]
|
||||
return true;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
|
@ -224,6 +224,7 @@ bool AP_MSP_Telem_DJI::get_rssi(float &rssi) const
|
|||
if (!displaying_stats_screen()) {
|
||||
return true;
|
||||
}
|
||||
#if AP_RSSI_ENABLED
|
||||
AP_RSSI* ap_rssi = AP::rssi();
|
||||
if (ap_rssi == nullptr) {
|
||||
return false;
|
||||
|
@ -231,6 +232,9 @@ bool AP_MSP_Telem_DJI::get_rssi(float &rssi) const
|
|||
if (!ap_rssi->enabled()) {
|
||||
return false;
|
||||
}
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
AP_OSD *osd = AP::osd();
|
||||
if (osd == nullptr) {
|
||||
return false;
|
||||
|
|
Loading…
Reference in New Issue