mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
AP_OSD: make packed decimal the default
and fix SITL char spacing
This commit is contained in:
parent
7320b15be4
commit
5a0354dfee
@ -75,7 +75,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||||||
// @Description: This sets options that change the display
|
// @Description: This sets options that change the display
|
||||||
// @Bitmask: 0:UseDecimalPack
|
// @Bitmask: 0:UseDecimalPack
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, 0),
|
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -55,7 +55,7 @@ private:
|
|||||||
static const uint8_t char_height = 18;
|
static const uint8_t char_height = 18;
|
||||||
static const uint8_t video_lines = 16; // PAL
|
static const uint8_t video_lines = 16; // PAL
|
||||||
static const uint8_t video_cols = 30;
|
static const uint8_t video_cols = 30;
|
||||||
static const uint8_t char_spacing = 1;
|
static const uint8_t char_spacing = 0;
|
||||||
|
|
||||||
// scaling factor to make it easier to read
|
// scaling factor to make it easier to read
|
||||||
static const uint8_t char_scale = 2;
|
static const uint8_t char_scale = 2;
|
||||||
|
Loading…
Reference in New Issue
Block a user