mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: add support for AP_VIDEOTX_ENABLED
This commit is contained in:
parent
8d1a362db7
commit
1096b7de3c
|
@ -901,6 +901,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(current2, "CURRENT2", 54, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
// @Param: VTX_PWR_EN
|
||||
// @DisplayName: VTX_PWR_EN
|
||||
// @Description: Displays VTX Power
|
||||
|
@ -916,6 +917,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(vtx_power, "VTX_PWR", 55, AP_OSD_Screen, AP_OSD_Setting),
|
||||
#endif // AP_VIDEOTX_ENABLED
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
// @Param: TER_HGT_EN
|
||||
|
@ -2111,9 +2113,9 @@ void AP_OSD_Screen::draw_current2(uint8_t x, uint8_t y)
|
|||
draw_current(1, x, y);
|
||||
}
|
||||
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
void AP_OSD_Screen::draw_vtx_power(uint8_t x, uint8_t y)
|
||||
{
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
AP_VideoTX *vtx = AP_VideoTX::get_singleton();
|
||||
if (!vtx) {
|
||||
return;
|
||||
|
@ -2124,8 +2126,9 @@ void AP_OSD_Screen::draw_vtx_power(uint8_t x, uint8_t y)
|
|||
powr = vtx->get_power_mw();
|
||||
}
|
||||
backend->write(x, y, !vtx->is_configuration_finished(), "%4hu%c", powr, SYMBOL(SYM_MW));
|
||||
#endif // AP_VIDEOTX_ENABLED
|
||||
}
|
||||
#endif // AP_VIDEOTX_ENABLED
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
void AP_OSD_Screen::draw_hgt_abvterr(uint8_t x, uint8_t y)
|
||||
{
|
||||
|
@ -2231,7 +2234,9 @@ void AP_OSD_Screen::draw(void)
|
|||
DRAW_SETTING(hdop);
|
||||
DRAW_SETTING(flightime);
|
||||
DRAW_SETTING(clk);
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
DRAW_SETTING(vtx_power);
|
||||
#endif
|
||||
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
DRAW_SETTING(esc_temp);
|
||||
|
|
Loading…
Reference in New Issue