mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: add and use AP_RSSI_ENABLED
This commit is contained in:
parent
03218b11ac
commit
b2a12f406f
|
@ -457,11 +457,13 @@ void AP_OSD::update_stats()
|
|||
if (voltage > 0) {
|
||||
_stats.min_voltage_v = fminf(_stats.min_voltage_v, voltage);
|
||||
}
|
||||
#if AP_RSSI_ENABLED
|
||||
// minimum rssi
|
||||
AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
|
||||
if (ap_rssi) {
|
||||
_stats.min_rssi = fminf(_stats.min_rssi, ap_rssi->read_receiver_rssi());
|
||||
}
|
||||
#endif
|
||||
// max airspeed either true or synthetic
|
||||
if (have_airspeed_estimate) {
|
||||
_stats.max_airspeed_mps = fmaxf(_stats.max_airspeed_mps, aspd_mps);
|
||||
|
|
|
@ -1410,6 +1410,7 @@ void AP_OSD_Screen::draw_restvolt(uint8_t x, uint8_t y)
|
|||
draw_bat_volt(0,VoltageType::RESTING_VOLTAGE,x,y);
|
||||
}
|
||||
|
||||
#if AP_RSSI_ENABLED
|
||||
void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y)
|
||||
{
|
||||
AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
|
||||
|
@ -1431,6 +1432,7 @@ void AP_OSD_Screen::draw_link_quality(uint8_t x, uint8_t y)
|
|||
}
|
||||
}
|
||||
}
|
||||
#endif // AP_RSSI_ENABLED
|
||||
|
||||
void AP_OSD_Screen::draw_current(uint8_t instance, uint8_t x, uint8_t y)
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue