AP_OSD: Add RX Link Quality Panel

This commit is contained in:
Hwurzburg 2021-07-14 14:28:34 -05:00 committed by Andrew Tridgell
parent 55af794a2f
commit ca92d73f25
2 changed files with 32 additions and 0 deletions

View File

@ -137,6 +137,7 @@ private:
AP_OSD_Setting altitude{true, 23, 8}; AP_OSD_Setting altitude{true, 23, 8};
AP_OSD_Setting bat_volt{true, 24, 1}; AP_OSD_Setting bat_volt{true, 24, 1};
AP_OSD_Setting rssi{true, 1, 1}; AP_OSD_Setting rssi{true, 1, 1};
AP_OSD_Setting link_quality{false,1,1};
AP_OSD_Setting restvolt{false, 24, 2}; AP_OSD_Setting restvolt{false, 24, 2};
AP_OSD_Setting avgcellvolt{false, 24, 3}; AP_OSD_Setting avgcellvolt{false, 24, 3};
AP_OSD_Setting current{true, 25, 2}; AP_OSD_Setting current{true, 25, 2};
@ -203,6 +204,7 @@ private:
void draw_avgcellvolt(uint8_t x, uint8_t y); void draw_avgcellvolt(uint8_t x, uint8_t y);
void draw_restvolt(uint8_t x, uint8_t y); void draw_restvolt(uint8_t x, uint8_t y);
void draw_rssi(uint8_t x, uint8_t y); void draw_rssi(uint8_t x, uint8_t y);
void draw_link_quality(uint8_t x, uint8_t y);
void draw_current(uint8_t x, uint8_t y); void draw_current(uint8_t x, uint8_t y);
void draw_current(uint8_t instance, uint8_t x, uint8_t y); void draw_current(uint8_t instance, uint8_t x, uint8_t y);
void draw_batused(uint8_t x, uint8_t y); void draw_batused(uint8_t x, uint8_t y);

View File

@ -994,6 +994,22 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
// @Description: Vertical position on screen // @Description: Vertical position on screen
// @Range: 0 15 // @Range: 0 15
AP_SUBGROUPINFO(rngf, "RNGF", 60, AP_OSD_Screen, AP_OSD_Setting), AP_SUBGROUPINFO(rngf, "RNGF", 60, AP_OSD_Screen, AP_OSD_Setting),
// @Param: LINK_Q_EN
// @DisplayName: LINK_Q_EN
// @Description: Displays Receiver link quality
// @Values: 0:Disabled,1:Enabled
// @Param: LINK_Q_X
// @DisplayName: LINK_Q_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: LINK_Q_Y
// @DisplayName: LINK_Q_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(link_quality, "LINK_Q", 61, AP_OSD_Screen, AP_OSD_Setting),
AP_GROUPEND AP_GROUPEND
}; };
@ -1271,6 +1287,19 @@ void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y)
} }
} }
void AP_OSD_Screen::draw_link_quality(uint8_t x, uint8_t y)
{
AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
if (ap_rssi) {
const int16_t lqv = ap_rssi->read_receiver_link_quality();
if (lqv < 0){
backend->write(x, y, false, "%c--", SYM_RSSI);
} else {
backend->write(x, y, false, "%c%2d", SYM_RSSI, lqv);
}
}
}
void AP_OSD_Screen::draw_current(uint8_t instance, uint8_t x, uint8_t y) void AP_OSD_Screen::draw_current(uint8_t instance, uint8_t x, uint8_t y)
{ {
float amps; float amps;
@ -2029,6 +2058,7 @@ void AP_OSD_Screen::draw(void)
DRAW_SETTING(avgcellvolt); DRAW_SETTING(avgcellvolt);
DRAW_SETTING(restvolt); DRAW_SETTING(restvolt);
DRAW_SETTING(rssi); DRAW_SETTING(rssi);
DRAW_SETTING(link_quality);
DRAW_SETTING(current); DRAW_SETTING(current);
DRAW_SETTING(batused); DRAW_SETTING(batused);
DRAW_SETTING(bat2used); DRAW_SETTING(bat2used);