AP_OSD: add extended RC link stats OSD fields
Adds RSSI dBm, SNR, LQ, Tx power and active antenna OSD fields
|
@ -85,7 +85,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||
// @Param: _OPTIONS
|
||||
// @DisplayName: OSD Options
|
||||
// @Description: This sets options that change the display
|
||||
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindArrow, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 5:TranslateArrows, 6:AviationStyleAH
|
||||
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindArrow, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 5:TranslateArrows, 6:AviationStyleAH, 7:Prefix LQ with RF Mode
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK),
|
||||
|
||||
|
@ -114,10 +114,10 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||
|
||||
// @Param: _W_RSSI
|
||||
// @DisplayName: RSSI warn level (in %)
|
||||
// @Description: Set level at which RSSI item will flash
|
||||
// @Range: 0 99
|
||||
// @Description: Set level at which RSSI item will flash (in positive % or negative dBm values as applicable). 30% or -100dBm are defaults.
|
||||
// @Range: -128 100
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_W_RSSI", 12, AP_OSD, warn_rssi, 30),
|
||||
AP_GROUPINFO("_W_RSSI", 12, AP_OSD, warn_rssi, AP_OSD_WARN_RSSI_DEFAULT),
|
||||
|
||||
// @Param: _W_NSAT
|
||||
// @DisplayName: NSAT warn level
|
||||
|
@ -214,6 +214,22 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("_W_ACRVOLT", 31, AP_OSD, warn_avgcellrestvolt, 3.6f),
|
||||
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
// @Param: _W_LQ
|
||||
// @DisplayName: RC link quality warn level (in %)
|
||||
// @Description: Set level at which RC_LQ item will flash (%)
|
||||
// @Range: 0 100
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_W_LQ", 33, AP_OSD, warn_lq, 50),
|
||||
|
||||
// @Param: _W_SNR
|
||||
// @DisplayName: RC link SNR warn level (in %)
|
||||
// @Description: Set level at which RC_SNR item will flash (in db)
|
||||
// @Range: -20 10
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_W_SNR", 34, AP_OSD, warn_snr, 0),
|
||||
#endif
|
||||
|
||||
#endif //osd enabled
|
||||
#if OSD_PARAM_ENABLED
|
||||
// @Group: 5_
|
||||
|
|
|
@ -48,8 +48,18 @@ class AP_MSP;
|
|||
#define PARAM_INDEX(key, idx, group) (uint32_t(uint32_t(key) << 23 | uint32_t(idx) << 18 | uint32_t(group)))
|
||||
#define PARAM_TOKEN_INDEX(token) PARAM_INDEX(AP_Param::get_persistent_key(token.key), token.idx, token.group_element)
|
||||
|
||||
#define AP_OSD_NUM_SYMBOLS 91
|
||||
#define AP_OSD_NUM_SYMBOLS 107
|
||||
#define OSD_MAX_INSTANCES 2
|
||||
|
||||
#if AP_OSD_LINK_STATS_EXTENSIONS_ENABLED
|
||||
// For the moment, these extra panels only work with CRSF protocol based RC systems
|
||||
#define AP_OSD_EXTENDED_LNK_STATS 1
|
||||
#define AP_OSD_WARN_RSSI_DEFAULT -100 // Default value for OSD RSSI panel warning, in dbm
|
||||
#else
|
||||
#define AP_OSD_EXTENDED_LNK_STATS 0
|
||||
#define AP_OSD_WARN_RSSI_DEFAULT 30 // Default value for OSD RSSI panel warning, in %
|
||||
#endif
|
||||
|
||||
/*
|
||||
class to hold one setting
|
||||
*/
|
||||
|
@ -226,6 +236,15 @@ private:
|
|||
#endif
|
||||
AP_OSD_Setting sidebars{false, 4, 5};
|
||||
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
// Extended link stats data panels
|
||||
AP_OSD_Setting rc_tx_power{false, 25, 12};
|
||||
AP_OSD_Setting rc_rssi_dbm{false, 6, 2};
|
||||
AP_OSD_Setting rc_snr{false, 23, 13};
|
||||
AP_OSD_Setting rc_active_antenna{false, 27, 13};
|
||||
AP_OSD_Setting rc_lq{false, 18, 2};
|
||||
#endif
|
||||
|
||||
// MSP OSD only
|
||||
AP_OSD_Setting crosshair;
|
||||
AP_OSD_Setting home_dist{true, 1, 1};
|
||||
|
@ -314,6 +333,16 @@ private:
|
|||
#endif
|
||||
void draw_rngf(uint8_t x, uint8_t y);
|
||||
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
// Extended link stats data panels
|
||||
bool is_btfl_fonts();
|
||||
void draw_rc_tx_power(uint8_t x, uint8_t y);
|
||||
void draw_rc_rssi_dbm(uint8_t x, uint8_t y);
|
||||
void draw_rc_snr(uint8_t x, uint8_t y);
|
||||
void draw_rc_active_antenna(uint8_t x, uint8_t y);
|
||||
void draw_rc_lq(uint8_t x, uint8_t y);
|
||||
#endif
|
||||
|
||||
struct {
|
||||
bool load_attempted;
|
||||
const char *str;
|
||||
|
@ -557,6 +586,11 @@ public:
|
|||
AP_Int8 failsafe_scr;
|
||||
AP_Int32 button_delay_ms;
|
||||
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
AP_Int8 warn_lq;
|
||||
AP_Int8 warn_snr;
|
||||
#endif
|
||||
|
||||
enum {
|
||||
OPTION_DECIMAL_PACK = 1U<<0,
|
||||
OPTION_INVERTED_WIND = 1U<<1,
|
||||
|
@ -565,6 +599,9 @@ public:
|
|||
OPTION_DISABLE_CROSSHAIR = 1U<<4,
|
||||
OPTION_BF_ARROWS = 1U<<5,
|
||||
OPTION_AVIATION_AH = 1U<<6,
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
OPTION_RF_MODE_ALONG_WITH_LQ = 1U<<7,
|
||||
#endif
|
||||
};
|
||||
|
||||
enum {
|
||||
|
|
|
@ -184,6 +184,22 @@ protected:
|
|||
static const uint8_t SYM_FENCE_DISABLED = 0xF6;
|
||||
static const uint8_t SYM_RNGFD = 0xF7;
|
||||
static const uint8_t SYM_LQ = 0xF8;
|
||||
static const uint8_t SYM_WATT = 0xAE;
|
||||
static const uint8_t SYM_WH = 0xAB;
|
||||
static const uint8_t SYM_DB = 0xF9;
|
||||
static const uint8_t SYM_DBM = 0xFA;
|
||||
static const uint8_t SYM_SNR = 0xFB;
|
||||
static const uint8_t SYM_ANT = 0xFC;
|
||||
static const uint8_t SYM_ARROW_RIGHT = 0xFD;
|
||||
static const uint8_t SYM_ARROW_LEFT = 0xFE;
|
||||
static const uint8_t SYM_G = 0xDF;
|
||||
static const uint8_t SYM_BATT_UNKNOWN = 0x97;
|
||||
static const uint8_t SYM_ROLL = 0xA9;
|
||||
static const uint8_t SYM_PITCH = 0xAF;
|
||||
static const uint8_t SYM_DPS = 0xAA;
|
||||
static const uint8_t SYM_HEADING = 0x89;
|
||||
static const uint8_t SYM_RADIUS = 0x7A;
|
||||
static const uint8_t SYM_FLAP = 0x23;
|
||||
|
||||
static const uint8_t SYM_SIDEBAR_R_ARROW = 0x09;
|
||||
static const uint8_t SYM_SIDEBAR_L_ARROW = 0x0A;
|
||||
|
@ -290,5 +306,21 @@ protected:
|
|||
SYM_SIDEBAR_H,
|
||||
SYM_SIDEBAR_I,
|
||||
SYM_SIDEBAR_J,
|
||||
SYM_WATT,
|
||||
SYM_WH,
|
||||
SYM_DB,
|
||||
SYM_DBM,
|
||||
SYM_SNR,
|
||||
SYM_ANT,
|
||||
SYM_ARROW_RIGHT,
|
||||
SYM_ARROW_LEFT,
|
||||
SYM_G,
|
||||
SYM_BATT_UNKNOWN,
|
||||
SYM_ROLL,
|
||||
SYM_PITCH,
|
||||
SYM_DPS,
|
||||
SYM_HEADING,
|
||||
SYM_RADIUS,
|
||||
SYM_FLAP,
|
||||
};
|
||||
};
|
||||
|
|
|
@ -44,6 +44,7 @@
|
|||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_RPM/AP_RPM.h>
|
||||
#include <AP_MSP/AP_MSP.h>
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||
#include <AP_WindVane/AP_WindVane.h>
|
||||
#endif
|
||||
|
@ -53,6 +54,11 @@
|
|||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
// We need to this file to access the CRSF telemetry objects which contains the link stats data
|
||||
#include <AP_RCProtocol/AP_RCProtocol_CRSF.h>
|
||||
#endif
|
||||
|
||||
const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
||||
|
||||
// @Param: ENABLE
|
||||
|
@ -1077,6 +1083,89 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info2[] = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("FONT", 4, AP_OSD_Screen, font_index, 0),
|
||||
#endif
|
||||
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
// @Param: RC_PWR_EN
|
||||
// @DisplayName: RC_PWR_EN
|
||||
// @Description: Displays the RC link transmit (TX) power in mW or W, depending on level
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: RC_PWR_X
|
||||
// @DisplayName: RC_PWR_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 59
|
||||
|
||||
// @Param: RC_PWR_Y
|
||||
// @DisplayName: RC_PWR_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 21
|
||||
AP_SUBGROUPINFO(rc_tx_power, "RC_PWR", 5, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: RSSIDBM_EN
|
||||
// @DisplayName: RSSIDBM_EN
|
||||
// @Description: Displays RC link signal strength in dBm
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: RSSIDBM_X
|
||||
// @DisplayName: RSSIDBM_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 59
|
||||
|
||||
// @Param: RSSIDBM_Y
|
||||
// @DisplayName: RSSIDBM_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 21
|
||||
AP_SUBGROUPINFO(rc_rssi_dbm, "RSSIDBM", 6, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: RC_SNR_EN
|
||||
// @DisplayName: RC_SNR_EN
|
||||
// @Description: Displays RC link signal to noise ratio in dB
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: RC_SNR_X
|
||||
// @DisplayName: RC_SNR_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 59
|
||||
|
||||
// @Param: RC_SNR_Y
|
||||
// @DisplayName: RC_SNR_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 21
|
||||
AP_SUBGROUPINFO(rc_snr, "RC_SNR", 7, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: RC_ANT_EN
|
||||
// @DisplayName: RC_ANT_EN
|
||||
// @Description: Displays the current RC link active antenna
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: RC_ANT_X
|
||||
// @DisplayName: RC_ANT_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 59
|
||||
|
||||
// @Param: RC_ANT_Y
|
||||
// @DisplayName: RC_ANT_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 21
|
||||
AP_SUBGROUPINFO(rc_active_antenna, "RC_ANT", 8, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: RC_LQ_EN
|
||||
// @DisplayName: RC_LQ_EN
|
||||
// @Description: Displays the RC link quality (uplink, 0 to 100%) and also RF mode if bit 7 of OSD_OPTIONS is set
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: RC_LQ_X
|
||||
// @DisplayName: RC_LQ_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 59
|
||||
|
||||
// @Param: RC_LQ_Y
|
||||
// @DisplayName: RC_LQ_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 21
|
||||
AP_SUBGROUPINFO(rc_lq, "RC_LQ", 9, AP_OSD_Screen, AP_OSD_Setting),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -1186,6 +1275,24 @@ uint8_t AP_OSD_AbstractScreen::symbols_lookup_table[AP_OSD_NUM_SYMBOLS];
|
|||
#define SYM_SIDEBAR_I 89
|
||||
#define SYM_SIDEBAR_J 90
|
||||
|
||||
#define SYM_WATT 91
|
||||
#define SYM_WH 92
|
||||
#define SYM_DB 93
|
||||
#define SYM_DBM 94
|
||||
#define SYM_SNR 95
|
||||
#define SYM_ANT 96
|
||||
#define SYM_ARROW_RIGHT 97
|
||||
#define SYM_ARROW_LEFT 98
|
||||
|
||||
#define SYM_G 99
|
||||
#define SYM_BATT_UNKNOWN 100
|
||||
#define SYM_ROLL 101
|
||||
#define SYM_PITCH 102
|
||||
#define SYM_DPS 103
|
||||
#define SYM_HEADING 104
|
||||
#define SYM_RADIUS 105
|
||||
#define SYM_FLAP 106
|
||||
|
||||
#define SYMBOL(n) AP_OSD_AbstractScreen::symbols_lookup_table[n]
|
||||
|
||||
// constructor
|
||||
|
@ -1923,6 +2030,142 @@ void AP_OSD_Screen::draw_esc_amps(uint8_t x, uint8_t y)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
bool AP_OSD_Screen::is_btfl_fonts()
|
||||
{
|
||||
const AP_MSP *p_msp = AP::msp();
|
||||
return (p_msp != nullptr && p_msp->is_option_enabled(AP_MSP::Option::DISPLAYPORT_BTFL_SYMBOLS));
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_rc_tx_power(uint8_t x, uint8_t y)
|
||||
{
|
||||
const int16_t tx_power = AP::crsf()->get_link_status().tx_power;
|
||||
bool btfl = is_btfl_fonts();
|
||||
if (tx_power > 0) {
|
||||
if (tx_power < 1000) {
|
||||
if (btfl) {
|
||||
backend->write(x, y, false, "%3d%cW", tx_power, SYMBOL(SYM_ALT_M)); // SYM_ALT_M (0x0C) is the BTFL character for a small "m"
|
||||
} else {
|
||||
backend->write(x, y, false, "%3d%c", tx_power, SYMBOL(SYM_MW));
|
||||
}
|
||||
} else {
|
||||
const float value_w = float(tx_power) * 0.001f;
|
||||
if (btfl) {
|
||||
backend->write(x, y, false, "%.2fW", value_w);
|
||||
} else {
|
||||
backend->write(x, y, false, "%.2f%c", value_w, SYMBOL(SYM_WATT));
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (btfl) {
|
||||
backend->write(x, y, false, "---%cW", SYMBOL(SYM_ALT_M));
|
||||
} else {
|
||||
backend->write(x, y, false, "---%c", SYMBOL(SYM_MW));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_rc_rssi_dbm(uint8_t x, uint8_t y)
|
||||
{
|
||||
const int8_t rssidbm = AP::crsf()->get_link_status().rssi_dbm;
|
||||
const bool blink = -rssidbm < osd->warn_rssi;
|
||||
bool btfl = is_btfl_fonts();
|
||||
|
||||
backend->write(x, y, blink, "%c", SYMBOL(SYM_RSSI));
|
||||
uint8_t new_x = x + 1;
|
||||
if (rssidbm >= 0) {
|
||||
if (btfl) {
|
||||
backend->write(new_x, y, blink, "%4dDBM", -rssidbm);
|
||||
} else {
|
||||
backend->write(new_x, y, blink, "%4d%c", -rssidbm, SYMBOL(SYM_DBM));
|
||||
}
|
||||
} else {
|
||||
if (btfl){
|
||||
backend->write(new_x, y, blink, "----DBM");
|
||||
} else {
|
||||
backend->write(new_x, y, blink, "----%c", SYMBOL(SYM_DBM));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_rc_snr(uint8_t x, uint8_t y)
|
||||
{
|
||||
const int8_t snr = AP::crsf()->get_link_status().snr;
|
||||
const bool blink = snr < osd->warn_snr;
|
||||
bool btfl = is_btfl_fonts();
|
||||
if (snr == INT8_MIN) {
|
||||
if (btfl) {
|
||||
backend->write(x, y, blink, "SNR---DB");
|
||||
} else {
|
||||
backend->write(x, y, blink, "%c---%c", SYMBOL(SYM_SNR), SYMBOL(SYM_DB));
|
||||
}
|
||||
} else {
|
||||
if (btfl) {
|
||||
backend->write(x, y, blink, "SNR%3dDB", snr);
|
||||
} else {
|
||||
backend->write(x, y, blink, "%c%3d%c", SYMBOL(SYM_SNR), snr, SYMBOL(SYM_DB));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_rc_active_antenna(uint8_t x, uint8_t y)
|
||||
{
|
||||
const int8_t active_antenna = AP::crsf()->get_link_status().active_antenna;
|
||||
bool btfl = is_btfl_fonts();
|
||||
if (active_antenna < 0) {
|
||||
if (btfl) {
|
||||
backend->write(x, y, false, "ANT-");
|
||||
} else {
|
||||
backend->write(x, y, false, "%c-", SYMBOL(SYM_ANT));
|
||||
}
|
||||
} else {
|
||||
if (btfl) {
|
||||
backend->write(x, y, false, "ANT%d", active_antenna + 1);
|
||||
} else {
|
||||
backend->write(x, y, false, "%c%d", SYMBOL(SYM_ANT), active_antenna + 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_rc_lq(uint8_t x, uint8_t y)
|
||||
{
|
||||
const int16_t lqv = AP::crsf()->get_link_status().link_quality;
|
||||
const bool blink = lqv < osd->warn_lq;
|
||||
bool btfl = is_btfl_fonts();
|
||||
bool prefix_rf = check_option(AP_OSD::OPTION_RF_MODE_ALONG_WITH_LQ);
|
||||
const int16_t rf_mode = AP::crsf()->get_link_status().rf_mode;
|
||||
if (lqv < 0) {
|
||||
if (btfl) {
|
||||
if (prefix_rf) {
|
||||
backend->write(x, y, blink, "LQ--:--");
|
||||
} else {
|
||||
backend->write(x, y, blink, "LQ--");
|
||||
}
|
||||
} else {
|
||||
if (prefix_rf) {
|
||||
backend->write(x, y, blink, "%c--:--", SYMBOL(SYM_LQ));
|
||||
} else {
|
||||
backend->write(x, y, blink, "%c--", SYMBOL(SYM_LQ));
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (btfl) {
|
||||
if (prefix_rf) {
|
||||
backend->write(x, y, blink, "LQ%2d:%2d", rf_mode, lqv);
|
||||
} else {
|
||||
backend->write(x, y, blink, "LQ%2d", lqv);
|
||||
}
|
||||
} else {
|
||||
if(prefix_rf) {
|
||||
backend->write(x, y, blink, "%c%2d:%2d", SYMBOL(SYM_LQ), rf_mode, lqv);
|
||||
} else {
|
||||
backend->write(x, y, blink, "%c%2d", SYMBOL(SYM_LQ), lqv);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // AP_OSD_EXTENDED_LNK_STATS
|
||||
|
||||
void AP_OSD_Screen::draw_gps_latitude(uint8_t x, uint8_t y)
|
||||
{
|
||||
AP_GPS & gps = AP::gps();
|
||||
|
@ -2367,6 +2610,14 @@ void AP_OSD_Screen::draw(void)
|
|||
DRAW_SETTING(eff);
|
||||
DRAW_SETTING(callsign);
|
||||
DRAW_SETTING(current2);
|
||||
|
||||
#if AP_OSD_EXTENDED_LNK_STATS
|
||||
DRAW_SETTING(rc_tx_power);
|
||||
DRAW_SETTING(rc_rssi_dbm);
|
||||
DRAW_SETTING(rc_snr);
|
||||
DRAW_SETTING(rc_active_antenna);
|
||||
DRAW_SETTING(rc_lq);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
#endif // OSD_ENABLED
|
||||
|
|
|
@ -22,3 +22,7 @@
|
|||
#ifndef AP_OSD_CALLSIGN_FROM_SD_ENABLED
|
||||
#define AP_OSD_CALLSIGN_FROM_SD_ENABLED (AP_FILESYSTEM_POSIX_ENABLED || AP_FILESYSTEM_FATFS_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_OSD_LINK_STATS_EXTENSIONS_ENABLED
|
||||
#define AP_OSD_LINK_STATS_EXTENSIONS_ENABLED 0 // Disabled by default to save flash, enable via custom build server
|
||||
#endif
|
||||
|
|
After Width: | Height: | Size: 176 KiB |
After Width: | Height: | Size: 203 KiB |
|
@ -0,0 +1,13 @@
|
|||
[config]
|
||||
count=1
|
||||
1=ARDU_Europa
|
||||
|
||||
[ARDU_Europa]
|
||||
imgname_720=WS_APN_Europa_24.png
|
||||
imgname_1080=WS_APN_Europa_36.png
|
||||
font_width_720=24
|
||||
font_height_720=36
|
||||
font_width_1080=36
|
||||
font_height_1080=54
|
||||
x_offset=0
|
||||
y_offset=0
|
Before Width: | Height: | Size: 10 KiB After Width: | Height: | Size: 39 KiB |
Before Width: | Height: | Size: 10 KiB After Width: | Height: | Size: 41 KiB |
Before Width: | Height: | Size: 39 KiB After Width: | Height: | Size: 42 KiB |
Before Width: | Height: | Size: 10 KiB After Width: | Height: | Size: 41 KiB |
Before Width: | Height: | Size: 9.8 KiB After Width: | Height: | Size: 40 KiB |