Hackover-Badge 2013
authorWintermute <wintermute@hannover.ccc.de>
Sat, 5 Oct 2013 21:27:11 +0000 (23:27 +0200)
committerWintermute <wintermute@hannover.ccc.de>
Sat, 5 Oct 2013 21:27:11 +0000 (23:27 +0200)
34 files changed:
Makefile
core/libc/string.c
core/usbhid-rom/usbconfig.c
core/usbhid-rom/usbconfig.h
core/usbhid-rom/usbhid.c
core/usbhid-rom/usbmsc.c [new file with mode: 0644]
core/usbhid-rom/usbmsc.h [new file with mode: 0644]
dataflash/at45db041d.c [new file with mode: 0644]
dataflash/at45db041d.h [new file with mode: 0644]
dataflash/diskio.c [new file with mode: 0644]
dataflash/diskio.h [new file with mode: 0644]
dataflash/integer.h [new file with mode: 0644]
dataflash/iobase.c [new file with mode: 0644]
dataflash/iobase.h [new file with mode: 0644]
lcd/Makefile [new file with mode: 0644]
lcd/Makefile.dep [new file with mode: 0644]
lcd/display.c [new file with mode: 0644]
lcd/display.h [new file with mode: 0644]
lcd/display_r0ket.c [new file with mode: 0644]
lcd/fonts/invaders.c [new file with mode: 0644]
lcd/fonts/invaders.h [new file with mode: 0644]
lcd/fonts/orbitron14.c [new file with mode: 0644]
lcd/fonts/orbitron14.h [new file with mode: 0644]
lcd/fonts/smallfonts.c [new file with mode: 0644]
lcd/fonts/smallfonts.h [new file with mode: 0644]
lcd/fonts/ubuntu18.c [new file with mode: 0644]
lcd/fonts/ubuntu18.h [new file with mode: 0644]
lcd/fonts/ubuntu29.c [new file with mode: 0644]
lcd/fonts/ubuntu29.h [new file with mode: 0644]
lcd/fonts/ubuntu36.c [new file with mode: 0644]
lcd/fonts/ubuntu36.h [new file with mode: 0644]
main.c
projectconfig.h
r0ketports.h [new file with mode: 0644]

index 34cc96c..b1f7810 100644 (file)
--- a/Makefile
+++ b/Makefile
@@ -113,7 +113,7 @@ OBJS += samsung_20T202DA2JA.o
 \r
 # ChaN FatFS and SD card support\r
 VPATH += drivers/fatfs\r
-OBJS += ff.o mmc.o\r
+OBJS += ff.o #mmc.o\r
 \r
 # Motors\r
 VPATH += drivers/motor/stepper\r
@@ -166,10 +166,17 @@ VPATH += core/usbhid-rom core/wdt core/usbcdc core/pwm core/iap
 VPATH += core/libc\r
 OBJS += stdio.o string.o\r
 OBJS += adc.o cpu.o cmd.o gpio.o i2c.o pmu.o ssp.o systick.o timer16.o\r
-OBJS += timer32.o uart.o uart_buf.o usbconfig.o usbhid.o\r
+OBJS += timer32.o uart.o uart_buf.o usbconfig.o usbhid.o usbmsc.o\r
 OBJS += wdt.o cdcuser.o cdc_buf.o usbcore.o usbdesc.o usbhw.o usbuser.o \r
 OBJS += sysinit.o pwm.o iap.o\r
 \r
+\r
+VPATH += lcd\r
+OBJS += display.o\r
+\r
+VPATH += dataflash\r
+OBJS += at45db041d.o iobase.o diskio.o\r
+\r
 ##########################################################################\r
 # GNU GCC compiler prefix and location\r
 ##########################################################################\r
@@ -212,10 +219,10 @@ OBJS += $(TARGET)_handlers.o LPC1xxx_startup.o
 # Compiler settings, parameters and flags\r
 ##########################################################################\r
 ifeq (TRUE,$(DEBUGBUILD))\r
-  CFLAGS  = -c -g -O0 $(INCLUDE_PATHS) -Wall -mthumb -ffunction-sections -fdata-sections -fmessage-length=0 -mcpu=$(CPU_TYPE) -DTARGET=$(TARGET) -fno-builtin $(OPTDEFINES)\r
+  CFLAGS  = -c -g -O0 $(INCLUDE_PATHS) -Wall -mthumb -ffunction-sections -fdata-sections -fmessage-length=0 -mcpu=$(CPU_TYPE) -DTARGET=$(TARGET) -fno-builtin $(OPTDEFINES) -std=c99\r
   ASFLAGS = -c -g -O0 $(INCLUDE_PATHS) -Wall -mthumb -ffunction-sections -fdata-sections -fmessage-length=0 -mcpu=$(CPU_TYPE) -D__ASSEMBLY__ -x assembler-with-cpp\r
 else\r
-  CFLAGS  = -c -g -Os $(INCLUDE_PATHS) -Wall -mthumb -ffunction-sections -fdata-sections -fmessage-length=0 -mcpu=$(CPU_TYPE) -DTARGET=$(TARGET) -fno-builtin $(OPTDEFINES)\r
+  CFLAGS  = -c -g -Os $(INCLUDE_PATHS) -Wall -mthumb -ffunction-sections -fdata-sections -fmessage-length=0 -mcpu=$(CPU_TYPE) -DTARGET=$(TARGET) -fno-builtin $(OPTDEFINES) -std=c99\r
   ASFLAGS = -c -g -Os $(INCLUDE_PATHS) -Wall -mthumb -ffunction-sections -fdata-sections -fmessage-length=0 -mcpu=$(CPU_TYPE) -D__ASSEMBLY__ -x assembler-with-cpp\r
 endif\r
 \r
index 3216009..3fe0b9c 100644 (file)
@@ -274,6 +274,8 @@ int strcmp(const char *s1, const char *s2)
   return (*(unsigned char *)s1 - *(unsigned char *)--s2);
 }
 
+char *strtok_r(char *s, const char *delim, char **last);
+
 char *strtok(char *s, const char *delim)
 {
   static char *last;
index 6fa0a7f..9aa787c 100644 (file)
@@ -53,40 +53,40 @@ const uint8_t USB_HIDStringDescriptor[] =
   /* Index 0x04: Manufacturer */
   0x1C,                              /* bLength */
   USB_STRING_DESCRIPTOR_TYPE,        /* bDescriptorType */
-  'm',0,
-  'i',0,
-  'c',0,
-  'r',0,
-  'o',0,
-  'B',0,
-  'u',0,
-  'i',0,
-  'l',0,
-  'd',0,
-  'e',0,
-  'r',0,
+  'C',0,
+  'C',0,
+  'C',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
   ' ',0,
   /* Index 0x20: Product */
   0x28,                              /* bLength */
   USB_STRING_DESCRIPTOR_TYPE,        /* bDescriptorType */
-  'L',0,
-  'P',0,
-  'C',0,
-  '1',0,
-  '3',0,
-  '4',0,
-  '3',0,
-  ' ',0,
-  'R',0,
+  'r',0,
+  '0',0,
+  'k',0,
   'e',0,
-  'f',0,
-  '.',0,
+  't',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
   ' ',0,
-  'B',0,
-  'o',0,
-  'a',0,
-  'r',0,
-  'd',0,
   ' ',0,
   /* Index 0x48: Serial Number */
   0x1A,                              /* bLength */
@@ -113,3 +113,74 @@ const uint8_t USB_HIDStringDescriptor[] =
   ' ',0,
   ' ',0,
 };
+
+/* USB String Descriptor (optional) */
+const uint8_t USB_MSCStringDescriptor[] = 
+{
+  /* Index 0x00: LANGID Codes */
+  0x04,                              /* bLength */
+  USB_STRING_DESCRIPTOR_TYPE,        /* bDescriptorType */
+  WBVAL(0x0409), /* US English */    /* wLANGID */
+  /* Index 0x04: Manufacturer */
+  0x1C,                              /* bLength */
+  USB_STRING_DESCRIPTOR_TYPE,        /* bDescriptorType */
+  'C',0,
+  'C',0,
+  'C',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  /* Index 0x20: Product */
+  0x28,                              /* bLength */
+  USB_STRING_DESCRIPTOR_TYPE,        /* bDescriptorType */
+  'r',0,
+  '0',0,
+  'k',0,
+  'e',0,
+  't',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  ' ',0,
+  /* Index 0x48: Serial Number */
+  0x1A,                              /* bLength */
+  USB_STRING_DESCRIPTOR_TYPE,        /* bDescriptorType */
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  '0',0,
+  /* Index 0x62: Interface 0, Alternate Setting 0 */
+  0x0E,                              /* bLength */
+  USB_STRING_DESCRIPTOR_TYPE,        /* bDescriptorType */
+  'M',0,
+  'e',0,
+  'm',0,
+  'o',0,
+  'r',0,
+  'y',0,
+};
index 9cc9110..d35d543 100644 (file)
@@ -41,8 +41,8 @@
 
 #include "projectconfig.h"
 
-#define USB_VENDOR_ID CFG_USB_VID      // Vendor ID
-#define USB_PROD_ID   CFG_USB_PID      // Product ID
+#define USB_VENDOR_ID 0x16c0   // Vendor ID
+#define USB_PROD_ID   0x08ac   // Product ID
 #define USB_DEVICE    0x0100   // Device ID
 
 #define WBVAL(x) ((x) & 0xFF),(((x) >> 8) & 0xFF)
@@ -59,8 +59,9 @@
 extern const uint8_t USB_DeviceDescriptor[];
 extern const uint8_t USB_ConfigDescriptor[];
 extern const uint8_t USB_HIDStringDescriptor[];
+extern const uint8_t USB_MSCStringDescriptor[];
 
 extern const uint8_t HID_ReportDescriptor[];
 extern const uint16_t HID_ReportDescSize;
 
-#endif
\ No newline at end of file
+#endif
index ce53742..fcbf7f2 100644 (file)
@@ -44,9 +44,9 @@
 
 #include "usbhid.h"
 
-USB_DEV_INFO DeviceInfo;
-HID_DEVICE_INFO HidDevInfo;
-ROM ** rom = (ROM **)0x1fff1ff8;
+static USB_DEV_INFO DeviceInfo;
+static HID_DEVICE_INFO HidDevInfo;
+static ROM ** rom = (ROM **)0x1fff1ff8;
 
 typedef struct usbhid_out_s
 {
diff --git a/core/usbhid-rom/usbmsc.c b/core/usbhid-rom/usbmsc.c
new file mode 100644 (file)
index 0000000..f757c7f
--- /dev/null
@@ -0,0 +1,98 @@
+#include "core/rom_drivers.h"
+#include "core/gpio/gpio.h"
+#include "dataflash/at45db041d.h"
+
+#include "usb.h"
+#include "usbconfig.h"
+#include "usbmsc.h"
+
+USB_DEV_INFO DeviceInfo;
+MSC_DEVICE_INFO MscDevInfo;
+ROM ** rom = (ROM **)0x1fff1ff8;
+char usbMSCenabled=0;
+
+void usbMSCWrite(uint32_t offset, uint8_t src[], uint32_t length) {
+    dataflash_random_write(src, offset, length);
+}
+
+void usbMSCRead(uint32_t offset, uint8_t dst[], uint32_t length) {
+    dataflash_random_read(dst, offset, length);
+}
+
+void usbMSCInit(void) {
+  dataflash_initialize();
+
+  // Setup USB clock
+  SCB_PDRUNCFG &= ~(SCB_PDSLEEPCFG_USBPAD_PD);        // Power-up USB PHY
+  SCB_PDRUNCFG &= ~(SCB_PDSLEEPCFG_USBPLL_PD);        // Power-up USB PLL
+
+  SCB_USBPLLCLKSEL = SCB_USBPLLCLKSEL_SOURCE_MAINOSC; // Select PLL Input
+  SCB_USBPLLCLKUEN = SCB_USBPLLCLKUEN_UPDATE;         // Update Clock Source
+  SCB_USBPLLCLKUEN = SCB_USBPLLCLKUEN_DISABLE;        // Toggle Update Register
+  SCB_USBPLLCLKUEN = SCB_USBPLLCLKUEN_UPDATE;
+
+  // Wait until the USB clock is updated
+  while (!(SCB_USBPLLCLKUEN & SCB_USBPLLCLKUEN_UPDATE));
+
+  // Set USB clock to 48MHz (12MHz x 4)
+  SCB_USBPLLCTRL = (SCB_USBPLLCTRL_MULT_4);
+  while (!(SCB_USBPLLSTAT & SCB_USBPLLSTAT_LOCK));    // Wait Until PLL Locked
+  SCB_USBCLKSEL = SCB_USBCLKSEL_SOURCE_USBPLLOUT;
+
+  // Set USB pin functions
+  // bsx says, its only needed for usb-hid. And it conflicts with btn_0
+//  IOCON_PIO0_1 &= ~IOCON_PIO0_1_FUNC_MASK;
+//  IOCON_PIO0_1 |= IOCON_PIO0_1_FUNC_CLKOUT;           // CLK OUT
+  IOCON_PIO0_3 &= ~IOCON_PIO0_3_FUNC_MASK;
+  IOCON_PIO0_3 |= IOCON_PIO0_3_FUNC_USB_VBUS;         // VBus
+  IOCON_PIO0_6 &= ~IOCON_PIO0_6_FUNC_MASK;
+  IOCON_PIO0_6 |= IOCON_PIO0_6_FUNC_USB_CONNECT;      // Soft Connect
+
+  // Disable internal resistor on VBUS (0.3)
+  gpioSetPullup(&IOCON_PIO0_3, gpioPullupMode_Inactive);
+
+  // workaround for long connect delay
+  *((uint32_t *)(0x10000054)) = 0x0;
+
+  // HID Device Info
+  volatile int n;
+  MscDevInfo.idVendor = USB_VENDOR_ID;
+  MscDevInfo.idProduct = USB_PROD_ID;
+  MscDevInfo.bcdDevice = USB_DEVICE;
+  MscDevInfo.StrDescPtr = (uint32_t)&USB_MSCStringDescriptor[0];
+  MscDevInfo.MSCInquiryStr = (uint32_t)&"r0ket DataFlash             "; // 28 char response to SCSI INQUIRY
+  MscDevInfo.BlockCount = 1024;
+  MscDevInfo.BlockSize = 512;
+  MscDevInfo.MemorySize = 1024*512;
+  MscDevInfo.MSC_Write = &usbMSCWrite;
+  MscDevInfo.MSC_Read = &usbMSCRead;
+
+  DeviceInfo.DevType = USB_DEVICE_CLASS_STORAGE;
+  DeviceInfo.DevDetailPtr = (uint32_t)&MscDevInfo;
+  
+  /* Enable Timer32_1, IOCON, and USB blocks (for USB ROM driver) */
+  SCB_SYSAHBCLKCTRL |= (SCB_SYSAHBCLKCTRL_CT32B1 | SCB_SYSAHBCLKCTRL_IOCON | SCB_SYSAHBCLKCTRL_USB_REG);
+
+  /* Use pll and pin init function in rom */
+  /* Warning: This will also set the system clock to 48MHz! */
+  // (*rom)->pUSBD->init_clk_pins();   
+
+  /* insert a delay between clk init and usb init */
+  for (n = 0; n < 75; n++) {__asm("nop");}
+
+  (*rom)->pUSBD->init(&DeviceInfo); /* USB Initialization */
+  (*rom)->pUSBD->connect(true);     /* USB Connect */
+  usbMSCenabled|=USB_MSC_ENABLEFLAG;
+}
+
+#if CFG_USBMSC
+void USB_IRQHandler() {
+  (*rom)->pUSBD->isr();
+}
+#endif
+
+void usbMSCOff(void) {
+  (*rom)->pUSBD->connect(false);     /* USB Disconnect */
+  usbMSCenabled&=~USB_MSC_ENABLEFLAG;
+}
+
diff --git a/core/usbhid-rom/usbmsc.h b/core/usbhid-rom/usbmsc.h
new file mode 100644 (file)
index 0000000..5d01583
--- /dev/null
@@ -0,0 +1,50 @@
+/**************************************************************************/
+/*! 
+    @file     usbhid.h
+    @author   K. Townsend (microBuilder.eu)
+
+    @section LICENSE
+
+    Software License Agreement (BSD License)
+
+    Copyright (c) 2010, microBuilder SARL
+    All rights reserved.
+
+    Redistribution and use in source and binary forms, with or without
+    modification, are permitted provided that the following conditions are met:
+    1. Redistributions of source code must retain the above copyright
+    notice, this list of conditions and the following disclaimer.
+    2. Redistributions in binary form must reproduce the above copyright
+    notice, this list of conditions and the following disclaimer in the
+    documentation and/or other materials provided with the distribution.
+    3. Neither the name of the copyright holders nor the
+    names of its contributors may be used to endorse or promote products
+    derived from this software without specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
+    EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+    WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+    DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
+    DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+    (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+    LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+    ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+    (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+    SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+/**************************************************************************/
+
+#ifndef _USBMSC_H_
+#define _USBMSC_H_
+
+#include "projectconfig.h"
+
+#define USB_MSC_ENABLEFLAG (1<<0)
+#define USB_CDC_ENABLEFLAG (1<<1)
+extern char usbMSCenabled;
+void usbMSCWrite(uint32_t offset, uint8_t src[], uint32_t length);
+void usbMSCRead(uint32_t offset, uint8_t dst[], uint32_t length);
+void usbMSCInit(void);
+void usbMSCOff(void);
+
+#endif
diff --git a/dataflash/at45db041d.c b/dataflash/at45db041d.c
new file mode 100644 (file)
index 0000000..a1d645a
--- /dev/null
@@ -0,0 +1,252 @@
+#include "projectconfig.h"
+#include "diskio.h"
+#include "iobase.h"
+#include "core/ssp/ssp.h"
+
+#include <r0ketports.h>
+
+/* Opcodes */
+#define OP_POWERDOWN      (0xB9)
+#define OP_RESUME         (0xAB)
+#define OP_PAGEREAD       (0xD2)
+#define OP_BUFFER1READ    (0xD1) /* Low Frequency (<=33MHz) */
+#define OP_BUFFER2READ    (0xD3) /* Low Frequency (<=33MHz) */
+#define OP_BUFFER1WRITE   (0x84)
+#define OP_BUFFER2WRITE   (0x87)
+#define OP_BUFFER1PROG    (0x83) /* with builtin erase */
+#define OP_BUFFER2PROG    (0x86) /* with builtin erase */
+#define OP_STATUSREAD     (0xD7)
+#define OP_DEVICEID       (0x9F)
+#define OP_PAGE2BUFFER1   (0x53)
+#define OP_PAGE2BUFFER2   (0x55)
+#define OP_BUFFER1PAGECMP (0x60)
+#define OP_BUFFER2PAGECMP (0x61)
+#define OP_AUTOREWRITE1   (0x58) /* Auto Page Rewrite throught Buffer 1 */
+#define OP_AUTOREWRITE2   (0x59) /* Auto Page Rewrite throught Buffer 2 */
+
+#define SB_READY          (1 << 7)
+#define SB_COMP           (1 << 6)
+#define SB_PROTECT        (1 << 1)
+#define SB_PAGESIZE       (1 << 0)
+
+#define MAX_PAGE          (2048)
+
+#define CS_LOW()    gpioSetValue(RB_SPI_CS_DF, 0)
+#define CS_HIGH()   gpioSetValue(RB_SPI_CS_DF, 1)
+
+static volatile DSTATUS status = STA_NOINIT;
+
+static void wait_for_ready() {
+    BYTE reg_status = 0xFF;
+
+    CS_LOW();
+    xmit_spi(OP_STATUSREAD);
+    do {
+        rcvr_spi_m((uint8_t *) &reg_status);
+    } while (!(reg_status & SB_READY));
+    CS_HIGH();
+}
+
+static void dataflash_powerdown() {
+    CS_LOW();
+    xmit_spi(OP_POWERDOWN);
+    CS_HIGH();
+}
+
+static void dataflash_resume() {
+    CS_LOW();
+    xmit_spi(OP_RESUME);
+    CS_HIGH();
+}
+
+DSTATUS dataflash_initialize() {
+    sspInit(0, sspClockPolarity_Low, sspClockPhase_RisingEdge);
+
+    gpioSetDir(RB_SPI_CS_DF, gpioDirection_Output);
+
+    dataflash_resume();
+    status &= ~STA_NOINIT;
+    return status;
+}
+
+DSTATUS dataflash_status() {
+    return status;
+}
+
+DRESULT dataflash_random_read(BYTE *buff, DWORD offset, DWORD length) {
+    if (!length) return RES_PARERR;
+    if (status & STA_NOINIT) return RES_NOTRDY;
+    if (offset+length > MAX_PAGE*256) return RES_PARERR;
+
+    do {
+        wait_for_ready();
+        DWORD pageaddr = ((offset/256) << 9) | (offset%256);
+        DWORD remaining = 256 - offset%256;
+        if (remaining > length) {
+            remaining = length;
+        }
+        length -= remaining;
+        offset += remaining;
+
+        CS_LOW();
+        xmit_spi(OP_PAGEREAD);
+        xmit_spi((BYTE)(pageaddr >> 16));
+        xmit_spi((BYTE)(pageaddr >> 8));
+        xmit_spi((BYTE)pageaddr);
+        xmit_spi(0x00); // follow up with 4 don't care bytes
+        xmit_spi(0x00);
+        xmit_spi(0x00);
+        xmit_spi(0x00);
+        do {
+            rcvr_spi_m(buff++);
+        } while (--remaining);
+        CS_HIGH();
+    } while (length);
+
+    return length ? RES_ERROR : RES_OK;
+}
+
+DRESULT dataflash_read(BYTE *buff, DWORD sector, BYTE count) {
+    return dataflash_random_read(buff, sector*512, count*512);
+}
+
+#if _READONLY == 0
+DRESULT dataflash_random_write(const BYTE *buff, DWORD offset, DWORD length) {
+    if (!length) return RES_PARERR;
+    if (status & STA_NOINIT) return RES_NOTRDY;
+    if (offset+length > MAX_PAGE*256) return RES_PARERR;
+
+    do {
+        wait_for_ready();
+        DWORD pageaddr = (offset/256) << 9;
+        DWORD buffaddr = (offset%256);
+        DWORD remaining = 256 - offset%256;
+        if (remaining > length) {
+            remaining = length;
+        }
+        length -= remaining;
+        offset += remaining;
+
+        // read page into the internal buffer
+        CS_LOW();
+        xmit_spi(OP_PAGE2BUFFER1);
+        xmit_spi((BYTE)(pageaddr >> 16));
+        xmit_spi((BYTE)(pageaddr >> 8));
+        xmit_spi((BYTE)pageaddr);
+        CS_HIGH();
+        wait_for_ready();
+
+        // write bytes into the dataflash buffer
+        CS_LOW();
+        xmit_spi(OP_BUFFER1WRITE);
+        xmit_spi((BYTE)(buffaddr >> 16));
+        xmit_spi((BYTE)(buffaddr >> 8));
+        xmit_spi((BYTE)buffaddr);
+        do {
+            xmit_spi(*buff++);
+        } while (--remaining);
+        CS_HIGH();
+        wait_for_ready();
+
+        // compare buffer with target memory page
+        CS_LOW();
+        xmit_spi(OP_BUFFER1PAGECMP);
+        xmit_spi((BYTE)(pageaddr >> 16));
+        xmit_spi((BYTE)(pageaddr >> 8));
+        xmit_spi((BYTE)pageaddr);
+        CS_HIGH();
+        wait_for_ready();
+        CS_LOW();
+        BYTE reg_status = 0xFF;
+        xmit_spi(OP_STATUSREAD);
+        rcvr_spi_m((uint8_t *) &reg_status);
+        CS_HIGH();
+
+        // trigger program only if data changed
+        if (reg_status & SB_COMP) {
+            CS_LOW();
+            xmit_spi(OP_BUFFER1PROG);
+            xmit_spi((BYTE)(pageaddr >> 16));
+            xmit_spi((BYTE)(pageaddr >> 8));
+            xmit_spi((BYTE)pageaddr);
+            CS_HIGH();
+        }
+    } while (length);
+
+    return length ? RES_ERROR : RES_OK;
+}
+
+DRESULT dataflash_write(const BYTE *buff, DWORD sector, BYTE count) {
+    return dataflash_random_write(buff, sector*512, count*512);
+}
+#endif /* _READONLY */
+
+#if _USE_IOCTL != 0
+DRESULT dataflash_ioctl(BYTE ctrl, void *buff) {
+    DRESULT res;
+    BYTE *ptr = buff;
+
+    res = RES_ERROR;
+
+
+    if (ctrl == CTRL_POWER) {
+        switch (*ptr) {
+            case 0: /* Sub control code == 0 (POWER_OFF) */
+                dataflash_powerdown();
+                res = RES_OK;
+                break;
+            case 1: /* Sub control code == 1 (POWER_ON) */
+                dataflash_resume();
+                res = RES_OK;
+                break;
+            case 2: /* Sub control code == 2 (POWER_GET) */
+                // TODO: figure out a way to retrieve the powerstate
+                *(ptr+1) = (BYTE)1;
+                res = RES_OK;
+                break;
+            default :
+                res = RES_PARERR;
+            }
+    } else {
+        if (status & STA_NOINIT) return RES_NOTRDY;
+
+        switch (ctrl) {
+            case CTRL_SYNC:
+                wait_for_ready();
+                res = RES_OK;
+                break;
+            case GET_SECTOR_COUNT:
+                // TODO: read from device ID register
+                *(WORD*)buff = MAX_PAGE/2;
+                res = RES_OK;
+                break;
+            case GET_SECTOR_SIZE:
+                *(WORD*)buff = 512;
+                res = RES_OK;
+                break;
+            case GET_BLOCK_SIZE:
+                *(WORD*)buff = 1;
+                res = RES_OK;
+                break;
+            default:
+                res = RES_PARERR;
+        }
+    }
+
+    return res;
+}
+#endif /* _USE_IOCTL != 0 */
+
+DWORD get_fattime () {
+  return 0;
+  /*
+    struct tm* tm=mygmtime(getSeconds());
+    DWORD t= (((tm->tm_year-80)<<9)|
+            ((tm->tm_mon+1)<<5)|
+            (tm->tm_mday))<<16 |
+            ((tm->tm_hour<<11)|
+            (tm->tm_min<<5)|
+            (tm->tm_sec>>1));
+    return t;
+  */
+}
diff --git a/dataflash/at45db041d.h b/dataflash/at45db041d.h
new file mode 100644 (file)
index 0000000..a19894c
--- /dev/null
@@ -0,0 +1,14 @@
+#ifndef _AT45DB041D_H
+#define _AT45DB041D_H 1
+
+#include "diskio.h"
+
+DSTATUS dataflash_initialize();
+DSTATUS dataflash_status();
+DRESULT dataflash_read(BYTE *buff, DWORD sector, BYTE count);
+DRESULT dataflash_random_read(BYTE *buff, DWORD offset, DWORD length);
+DRESULT dataflash_write(const BYTE *buff, DWORD sector, BYTE count);
+DRESULT dataflash_random_write(const BYTE *buff, DWORD offset, DWORD length);
+DRESULT dataflash_ioctl(BYTE ctrl, void *buff);
+
+#endif /* _AT45DB041D_H */
diff --git a/dataflash/diskio.c b/dataflash/diskio.c
new file mode 100644 (file)
index 0000000..1c0f7fb
--- /dev/null
@@ -0,0 +1,89 @@
+#include "projectconfig.h"
+#include "diskio.h"
+
+#if CFG_HAVE_SDCARD == 1
+#include "mmc.h"
+#endif
+
+#include "at45db041d.h"
+
+/* diskio interface */
+
+DSTATUS disk_initialize(BYTE drv) {
+    #if CFG_HAVE_SDCARD == 1
+    switch (drv) {
+        case 0:
+    #endif
+            return dataflash_initialize();
+    #if CFG_HAVE_SDCARD == 1
+        case 1:
+            return mmc_initialize();
+        default:
+            return STA_NOINIT;
+    }
+    #endif
+}
+
+DSTATUS disk_status(BYTE drv) {
+    #if CFG_HAVE_SDCARD == 1
+    switch (drv) {
+        case 0:
+    #endif
+            return dataflash_status();
+    #if CFG_HAVE_SDCARD == 1
+        case 1:
+            return mmc_status();
+        default:
+            return STA_NOINIT;
+    }
+    #endif
+}
+
+DRESULT disk_read(BYTE drv, BYTE *buff, DWORD sector, BYTE count) {
+    #if CFG_HAVE_SDCARD == 1
+    switch (drv) {
+        case 0:
+    #endif
+            return dataflash_read(buff, sector, count);
+    #if CFG_HAVE_SDCARD == 1
+        case 1:
+            return mmc_read(buff, sector, count);
+        default:
+            return RES_PARERR;
+    }
+    #endif
+}
+
+#if _READONLY == 0
+DRESULT disk_write(BYTE drv, const BYTE *buff, DWORD sector, BYTE count) {
+    #if CFG_HAVE_SDCARD == 1
+    switch (drv) {
+        case 0:
+    #endif
+            return dataflash_write(buff, sector, count);
+    #if CFG_HAVE_SDCARD == 1
+        case 1:
+            return mmc_write(buff, sector, count);
+        default:
+            return RES_PARERR;
+    }
+    #endif
+}
+#endif /* _READONLY == 0 */
+
+#if _USE_IOCTL != 0
+DRESULT disk_ioctl(BYTE drv, BYTE ctrl, void *buff) {
+    #if CFG_HAVE_SDCARD == 1
+    switch (drv) {
+        case 0:
+    #endif
+            return dataflash_ioctl(ctrl, buff);
+    #if CFG_HAVE_SDCARD == 1
+        case 1:
+            return mmc_ioctl(ctrl, buff);
+        default:
+            return RES_PARERR;
+    }
+    #endif
+}
+#endif /* _USE_IOCTL != 0 */
diff --git a/dataflash/diskio.h b/dataflash/diskio.h
new file mode 100644 (file)
index 0000000..bac393d
--- /dev/null
@@ -0,0 +1,84 @@
+/*-----------------------------------------------------------------------\r
+/  Low level disk interface modlue include file\r
+/-----------------------------------------------------------------------*/\r
+\r
+#ifndef _DISKIO\r
+\r
+#define _READONLY      0       /* 1: Remove write functions */\r
+#define _USE_IOCTL     1       /* 1: Use disk_ioctl fucntion */\r
+\r
+#include "integer.h"\r
+\r
+\r
+/* Status of Disk Functions */\r
+typedef BYTE   DSTATUS;\r
+\r
+/* Results of Disk Functions */\r
+typedef enum {\r
+       RES_OK = 0,             /* 0: Successful */\r
+       RES_ERROR,              /* 1: R/W Error */\r
+       RES_WRPRT,              /* 2: Write Protected */\r
+       RES_NOTRDY,             /* 3: Not Ready */\r
+       RES_PARERR              /* 4: Invalid Parameter */\r
+} DRESULT;\r
+\r
+\r
+/*---------------------------------------*/\r
+/* Prototypes for disk control functions */\r
+\r
+int assign_drives (int, int);\r
+DSTATUS disk_initialize (BYTE);\r
+DSTATUS disk_status (BYTE);\r
+DRESULT disk_read (BYTE, BYTE*, DWORD, BYTE);\r
+#if    _READONLY == 0\r
+DRESULT disk_write (BYTE, const BYTE*, DWORD, BYTE);\r
+#endif\r
+DRESULT disk_ioctl (BYTE, BYTE, void*);\r
+\r
+\r
+\r
+/* Disk Status Bits (DSTATUS) */\r
+\r
+#define STA_NOINIT             0x01    /* Drive not initialized */\r
+#define STA_NODISK             0x02    /* No medium in the drive */\r
+#define STA_PROTECT            0x04    /* Write protected */\r
+\r
+\r
+/* Command code for disk_ioctrl fucntion */\r
+\r
+/* Generic command (defined for FatFs) */\r
+#define CTRL_SYNC                      0       /* Flush disk cache (for write functions) */\r
+#define GET_SECTOR_COUNT       1       /* Get media size (for only f_mkfs()) */\r
+#define GET_SECTOR_SIZE                2       /* Get sector size (for multiple sector size (_MAX_SS >= 1024)) */\r
+#define GET_BLOCK_SIZE         3       /* Get erase block size (for only f_mkfs()) */\r
+#define CTRL_ERASE_SECTOR      4       /* Force erased a block of sectors (for only _USE_ERASE) */\r
+\r
+/* Generic command */\r
+#define CTRL_POWER                     5       /* Get/Set power status */\r
+#define CTRL_LOCK                      6       /* Lock/Unlock media removal */\r
+#define CTRL_EJECT                     7       /* Eject media */\r
+\r
+/* MMC/SDC specific ioctl command */\r
+#define MMC_GET_TYPE           10      /* Get card type */\r
+#define MMC_GET_CSD                    11      /* Get CSD */\r
+#define MMC_GET_CID                    12      /* Get CID */\r
+#define MMC_GET_OCR                    13      /* Get OCR */\r
+#define MMC_GET_SDSTAT         14      /* Get SD status */\r
+\r
+/* ATA/CF specific ioctl command */\r
+#define ATA_GET_REV                    20      /* Get F/W revision */\r
+#define ATA_GET_MODEL          21      /* Get model name */\r
+#define ATA_GET_SN                     22      /* Get serial number */\r
+\r
+/* NAND specific ioctl command */\r
+#define NAND_FORMAT                    30      /* Create physical format */\r
+\r
+/* Card type flags (CardType) */\r
+#define CT_MMC              0x01    /* MMC ver 3 */\r
+#define CT_SD1              0x02    /* SD ver 1 */\r
+#define CT_SD2              0x04    /* SD ver 2 */\r
+#define CT_SDC              (CT_SD1|CT_SD2) /* SD */\r
+#define CT_BLOCK            0x08    /* Block addressing */\r
+\r
+#define _DISKIO\r
+#endif\r
diff --git a/dataflash/integer.h b/dataflash/integer.h
new file mode 100644 (file)
index 0000000..137b988
--- /dev/null
@@ -0,0 +1,37 @@
+/*-------------------------------------------*/\r
+/* Integer type definitions for FatFs module */\r
+/*-------------------------------------------*/\r
+\r
+#ifndef _INTEGER\r
+#define _INTEGER\r
+\r
+#ifdef _WIN32  /* FatFs development platform */\r
+\r
+#include <windows.h>\r
+#include <tchar.h>\r
+\r
+#else                  /* Embedded platform */\r
+\r
+/* These types must be 16-bit, 32-bit or larger integer */\r
+typedef int                            INT;\r
+typedef unsigned int   UINT;\r
+\r
+/* These types must be 8-bit integer */\r
+typedef char                   CHAR;\r
+typedef unsigned char  UCHAR;\r
+typedef unsigned char  BYTE;\r
+\r
+/* These types must be 16-bit integer */\r
+typedef short                  SHORT;\r
+typedef unsigned short USHORT;\r
+typedef unsigned short WORD;\r
+typedef unsigned short WCHAR;\r
+\r
+/* These types must be 32-bit integer */\r
+typedef long                   LONG;\r
+typedef unsigned long  ULONG;\r
+typedef unsigned long  DWORD;\r
+\r
+#endif\r
+\r
+#endif\r
diff --git a/dataflash/iobase.c b/dataflash/iobase.c
new file mode 100644 (file)
index 0000000..08a8ba0
--- /dev/null
@@ -0,0 +1,21 @@
+#include "diskio.h"
+#include "core/ssp/ssp.h"
+
+/*-----------------------------------------------------------------------*/
+/* Transmit a byte via SPI  (Platform dependent)                  */
+/*-----------------------------------------------------------------------*/
+void xmit_spi(BYTE dat) {
+    sspSend(0, (uint8_t*) &dat, 1);
+}
+
+/*-----------------------------------------------------------------------*/
+/* Receive a byte from MMC via SPI  (Platform dependent)                 */
+/*-----------------------------------------------------------------------*/
+BYTE rcvr_spi (void) {
+    BYTE data = 0;
+
+    sspReceive(0, &data, 1);
+
+    return data;
+}
+
diff --git a/dataflash/iobase.h b/dataflash/iobase.h
new file mode 100644 (file)
index 0000000..040834a
--- /dev/null
@@ -0,0 +1,12 @@
+
+void xmit_spi(BYTE dat);
+
+BYTE rcvr_spi (void);
+
+/* Alternative macro to receive data fast */
+
+#define rcvr_spi_m(dst) \
+    do { \
+        sspReceive(0, (uint8_t*)(dst), 1); \
+    } while(0)
+
diff --git a/lcd/Makefile b/lcd/Makefile
new file mode 100644 (file)
index 0000000..2a267e0
--- /dev/null
@@ -0,0 +1,29 @@
+##########################################################################
+# User configuration and firmware specific object files        
+##########################################################################
+
+OBJS =
+
+OBJS += display.o
+#OBJS += render.o
+#OBJS += decoder.o
+#OBJS += backlight.o
+#OBJS += print.o
+#OBJS += image.o
+#OBJS += o.o
+
+LIBNAME=lcd
+
+##########################################################################
+# GNU GCC compiler flags
+##########################################################################
+ROOT_PATH?= ..
+INCLUDE_PATHS = -I$(ROOT_PATH) -I../core -I.
+
+include $(ROOT_PATH)/Makefile.inc
+
+##########################################################################
+# Actual work
+##########################################################################
+
+include $(ROOT_PATH)/Makefile.util
diff --git a/lcd/Makefile.dep b/lcd/Makefile.dep
new file mode 100644 (file)
index 0000000..9d8dcff
--- /dev/null
@@ -0,0 +1,38 @@
+display.o: display.c display.h ../sysdefs.h ../core/lpc134x.h \
+ ../core/sysdefs.h ../core/../sysdefs.h ../core/projectconfig.h \
+ ../core/lpc134x.h ../core/ssp/ssp.h ../core/projectconfig.h \
+ ../core/gpio/gpio.h ../core/gpio/gpio.h ../basic/basic.h \
+ ../core/adc/adc.h ../basic/uuid.h ../basic/idle.h ../basic/simpletime.h \
+ ../basic/config.h ../usb/usbmsc.h
+render.o: render.c ../sysdefs.h render.h display.h fonts.h decoder.h \
+ fonts.h ../basic/basic.h ../core/gpio/gpio.h ../core/projectconfig.h \
+ ../core/lpc134x.h ../core/sysdefs.h ../core/../sysdefs.h \
+ ../core/projectconfig.h ../core/adc/adc.h ../basic/uuid.h \
+ ../basic/idle.h ../basic/simpletime.h fonts/smallfonts.h ../lcd/fonts.h \
+ ../filesystem/ff.h ../filesystem/integer.h ../filesystem/ffconf.h \
+ render.h
+decoder.o: decoder.c fonts.h ../sysdefs.h render.h display.h fonts.h
+backlight.o: backlight.c ../core/lpc134x.h ../core/sysdefs.h \
+ ../core/../sysdefs.h ../core/projectconfig.h ../core/lpc134x.h \
+ ../sysdefs.h ../core/gpio/gpio.h ../core/projectconfig.h \
+ ../basic/basic.h ../core/adc/adc.h ../basic/uuid.h ../basic/idle.h \
+ ../basic/simpletime.h
+print.o: print.c display.h ../sysdefs.h render.h display.h fonts.h \
+ fonts.h print.h fonts/smallfonts.h ../lcd/fonts.h
+image.o: image.c ../core/sysinit.h ../core/projectconfig.h \
+ ../core/lpc134x.h ../core/sysdefs.h ../core/../sysdefs.h \
+ ../core/gpio/gpio.h ../core/projectconfig.h ../core/systick/systick.h \
+ ../basic/basic.h ../core/adc/adc.h ../basic/uuid.h ../basic/idle.h \
+ ../basic/simpletime.h ../lcd/lcd.h ../lcd/backlight.h ../lcd/decoder.h \
+ ../lcd/display.h ../sysdefs.h ../lcd/render.h ../lcd/display.h \
+ ../lcd/fonts.h ../lcd/fonts/smallfonts.h ../lcd/fonts.h ../lcd/o.h \
+ ../filesystem/ff.h ../filesystem/integer.h ../filesystem/ffconf.h
+o.o: o.c display.h ../sysdefs.h o.h
+invaders.o: fonts/invaders.c fonts/invaders.h ../lcd/fonts.h ../sysdefs.h
+ubuntu18.o: fonts/ubuntu18.c fonts/ubuntu18.h ../lcd/fonts.h ../sysdefs.h
+ubuntu36.o: fonts/ubuntu36.c fonts/ubuntu36.h ../lcd/fonts.h ../sysdefs.h
+smallfonts.o: fonts/smallfonts.c fonts/smallfonts.h ../lcd/fonts.h \
+ ../sysdefs.h
+orbitron14.o: fonts/orbitron14.c fonts/orbitron14.h ../lcd/fonts.h \
+ ../sysdefs.h
+ubuntu29.o: fonts/ubuntu29.c fonts/ubuntu29.h ../lcd/fonts.h ../sysdefs.h
diff --git a/lcd/display.c b/lcd/display.c
new file mode 100644 (file)
index 0000000..4849753
--- /dev/null
@@ -0,0 +1,115 @@
+#include "display.h"
+
+#include <core/ssp/ssp.h>
+#include <core/gpio/gpio.h>
+#include <core/systick/systick.h>
+#include <sysdefs.h>
+#include <lpc134x.h>
+
+#include <r0ketports.h>
+
+static void lcd_select() {
+    /* the LCD requires 9-Bit frames */
+  uint32_t configReg = ( SSP_SSP0CR0_DSS_9BIT     // Data size = 9-bit
+                         | SSP_SSP0CR0_FRF_SPI    // Frame format = SPI
+                         | SSP_SSP0CR0_SCR_8);    // Serial clock rate = 8
+  SSP_SSP0CR0 = configReg;
+  gpioSetValue(RB_LCD_CS, 0);
+}
+
+static void lcd_deselect() {
+  gpioSetValue(RB_LCD_CS, 1);
+  /* reset the bus to 8-Bit frames that everyone else uses */
+  uint32_t configReg = ( SSP_SSP0CR0_DSS_8BIT     // Data size = 8-bit
+                         | SSP_SSP0CR0_FRF_SPI    // Frame format = SPI
+                         | SSP_SSP0CR0_SCR_8);    // Serial clock rate = 8
+  SSP_SSP0CR0 = configReg;
+}
+
+static inline void lcd_write(uint16_t frame) {
+  while ((SSP_SSP0SR & (SSP_SSP0SR_TNF_NOTFULL | SSP_SSP0SR_BSY_BUSY)) != SSP_SSP0SR_TNF_NOTFULL);
+  SSP_SSP0DR = frame;
+  while ((SSP_SSP0SR & (SSP_SSP0SR_BSY_BUSY|SSP_SSP0SR_RNE_NOTEMPTY)) != SSP_SSP0SR_RNE_NOTEMPTY);
+    /* clear the FIFO */
+  frame = SSP_SSP0DR;
+}
+
+static void lcd_write_command(uint8_t data) { lcd_write(         data); }
+static void lcd_write_data   (uint8_t data) { lcd_write(0x0100 | data); }
+
+void badge_display_init(void) {
+  sspInit(0, sspClockPolarity_Low, sspClockPhase_RisingEdge);
+
+  gpioSetValue(RB_LCD_CS , 1);
+  gpioSetValue(RB_LCD_RST, 1);
+
+  gpioSetDir  (RB_LCD_CS , gpioDirection_Output);
+  gpioSetDir  (RB_LCD_RST, gpioDirection_Output);
+
+  systickDelay(100);
+  gpioSetValue(RB_LCD_RST, 0);
+  systickDelay(100);
+  gpioSetValue(RB_LCD_RST, 1);
+  systickDelay(100);
+  /*
+  int id = lcdRead(220);
+
+  if(id == 14) {
+    gpioSetDir(1, 7, gpioDirection_Output);
+    gpioSetValue(1, 7, 1);
+  }
+  */
+
+/* Small Nokia 1200 LCD docs:
+ *           clear/ set
+ *  on       0xae / 0xaf
+ *  invert   0xa6 / 0xa7
+ *  mirror-x 0xA0 / 0xA1
+ *  mirror-y 0xc7 / 0xc8
+ *
+ *  0x20+x contrast (0=black - 0x2e)
+ *  0x40+x offset in rows from top (-0x7f)
+ *  0x80+x contrast? (0=black -0x9f?)
+ *  0xd0+x black lines from top? (-0xdf?)
+ *
+ */
+  lcd_select();
+
+  /* Decoded:
+   * E2: Internal reset
+   * AF: Display on/off: DON = 1
+   * A1: undefined?
+   * A4: all on/normal: DAL = 0
+   * 2F: charge pump on/off: PC = 1
+   * B0: set y address: Y[0-3] = 0
+   * 10: set x address (upper bits): X[6-4] = 0
+   */
+  static uint8_t const initseq[]= { 0xE2, 0xAF, // Display ON
+                                   //      0xA1,       // Mirror-X
+                                   0xc8, // mirror-y
+                                   0xa7, // invert (1 = black)
+                                   0xA4, 0x2F,
+                                   0xB0, 0x10,
+                                   0x9f, 0x24 };
+  for(uint8_t i = 0; i < sizeof(initseq); ++i){
+    lcd_write_command(initseq[i]);
+    systickDelay(5);
+  }
+
+  lcd_deselect();
+}
+
+void badge_framebuffer_flush(badge_framebuffer const *fb) {
+  lcd_select();
+
+  lcd_write_command(0xb0);
+  lcd_write_command(0x10);
+  lcd_write_command(0x00);
+
+  
+  for(int i = 0; i < 9 * 96; ++i) {
+    lcd_write_data(fb->data[0][i]);
+  }
+
+  lcd_deselect();
+}
diff --git a/lcd/display.h b/lcd/display.h
new file mode 100644 (file)
index 0000000..35bc8fa
--- /dev/null
@@ -0,0 +1,71 @@
+#ifndef INCLUDED_BADGE2013_MOCKUP_DISPLAY_H
+#define INCLUDED_BADGE2013_MOCKUP_DISPLAY_H
+
+#include <stdint.h>
+#include <stddef.h>
+#include <string.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+  enum {
+    BADGE_DISPLAY_WIDTH         = 96,
+    BADGE_DISPLAY_HEIGHT        = 68,
+
+    BADGE_DISPLAY_STRIPE_HEIGHT = 8,
+    BADGE_DISPLAY_STRIPE_COUNT  = (BADGE_DISPLAY_HEIGHT - 1) / BADGE_DISPLAY_STRIPE_HEIGHT + 1
+  };
+
+  typedef uint8_t badge_display_stripe[BADGE_DISPLAY_WIDTH];
+  typedef struct {
+    badge_display_stripe data[BADGE_DISPLAY_STRIPE_COUNT];
+  } badge_framebuffer;
+
+  void badge_display_init(void);
+  void badge_framebuffer_flush(badge_framebuffer const *fb);
+
+  static inline void badge_framebuffer_clear(badge_framebuffer *fb) {
+    memset(fb, 0, sizeof(*fb));
+  }
+
+  static inline uint8_t badge_framebuffer_pixel(badge_framebuffer *fb,
+                                               uint8_t x,
+                                               uint8_t y) {
+    return fb->data[y / BADGE_DISPLAY_STRIPE_HEIGHT][x] >> (y % BADGE_DISPLAY_STRIPE_HEIGHT) & 1;
+  }
+
+  static inline void badge_framebuffer_pixel_on(badge_framebuffer *fb,
+                                               uint8_t x,
+                                               uint8_t y) {
+    fb->data[y / BADGE_DISPLAY_STRIPE_HEIGHT][x] |= 1 << (y % BADGE_DISPLAY_STRIPE_HEIGHT);
+  }
+
+  static inline void badge_framebuffer_pixel_off(badge_framebuffer *fb,
+                                                uint8_t x,
+                                                uint8_t y) {
+    fb->data[y / BADGE_DISPLAY_STRIPE_HEIGHT][x] &= ~(1 << (y % BADGE_DISPLAY_STRIPE_HEIGHT));
+  }
+
+  static inline void badge_framebuffer_pixel_flip(badge_framebuffer *fb,
+                                                 uint8_t x,
+                                                 uint8_t y) {
+    fb->data[y / BADGE_DISPLAY_STRIPE_HEIGHT][x] ^= 1 << (y % BADGE_DISPLAY_STRIPE_HEIGHT);
+  }
+
+  static inline void badge_framebuffer_pixel_set(badge_framebuffer *fb,
+                                                uint8_t x,
+                                                uint8_t y,
+                                                uint8_t val) {
+    if(val) {
+      badge_framebuffer_pixel_on (fb, x, y);
+    } else {
+      badge_framebuffer_pixel_off(fb, x, y);
+    }
+  }
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/lcd/display_r0ket.c b/lcd/display_r0ket.c
new file mode 100644 (file)
index 0000000..8d2d29c
--- /dev/null
@@ -0,0 +1,488 @@
+#include <string.h>
+
+#include <display.h>
+#include <sysdefs.h>
+#include "lpc134x.h"
+#include "core/ssp/ssp.h"
+#include "gpio/gpio.h"
+#include "basic/basic.h"
+#include "basic/config.h"
+#include "usb/usbmsc.h"
+
+
+#define DISPLAY_N1200 0
+#define DISPLAY_N1600 1
+
+#define MODE 8 /* 8 or 16 */
+
+#if MODE == 8
+#define putpix(x) _helper_pixel8(x)
+#define px_INIT_MODE 2
+#define px_PACK(r,g,b) COLORPACK_RGB332(r,g,b)
+#define px_type uint8_t
+#else
+ #if MODE == 12
+ #define putpix(x) _helper_pixel12(x)
+ #define px_INIT_MODE 3
+ #define px_PACK(r,g,b) COLORPACK_RGB444(r,g,b)
+ #define px_type uint16_t
+ #else
+ #define putpix(x) _helper_pixel16(x)
+ #define px_INIT_MODE 5
+ #define px_PACK(r,g,b) COLORPACK_RGB565(r,g,b)
+ #define px_type uint16_t
+ #endif
+#endif
+
+/**************************************************************************/
+/* Utility routines to manage nokia display */
+/**************************************************************************/
+
+uint8_t lcdBuffer[RESX*RESY_B];
+uint32_t intstatus; // Caches USB interrupt state
+                    // (need to disable MSC while displaying)
+uint8_t displayType;
+
+#define TYPE_CMD    0
+#define TYPE_DATA   1
+
+static void lcd_select() {
+#if CFG_USBMSC
+    if(usbMSCenabled){
+        intstatus=USB_DEVINTEN;
+        USB_DEVINTEN=0;
+    };
+#endif
+    /* the LCD requires 9-Bit frames */
+    uint32_t configReg = ( SSP_SSP0CR0_DSS_9BIT     // Data size = 9-bit
+                  | SSP_SSP0CR0_FRF_SPI             // Frame format = SPI
+                  | SSP_SSP0CR0_SCR_8);             // Serial clock rate = 8
+    SSP_SSP0CR0 = configReg;
+    gpioSetValue(RB_LCD_CS, 0);
+}
+
+static void lcd_deselect() {
+    gpioSetValue(RB_LCD_CS, 1);
+    /* reset the bus to 8-Bit frames that everyone else uses */
+    uint32_t configReg = ( SSP_SSP0CR0_DSS_8BIT     // Data size = 8-bit
+                  | SSP_SSP0CR0_FRF_SPI             // Frame format = SPI
+                  | SSP_SSP0CR0_SCR_8);             // Serial clock rate = 8
+    SSP_SSP0CR0 = configReg;
+#if CFG_USBMSC
+    if(usbMSCenabled){
+        USB_DEVINTEN=intstatus;
+    };
+#endif
+}
+
+static void lcdWrite(uint8_t cd, uint8_t data) {
+    uint16_t frame = 0x0;
+
+    frame = cd << 8;
+    frame |= data;
+
+    while ((SSP_SSP0SR & (SSP_SSP0SR_TNF_NOTFULL | SSP_SSP0SR_BSY_BUSY)) != SSP_SSP0SR_TNF_NOTFULL);
+    SSP_SSP0DR = frame;
+    while ((SSP_SSP0SR & (SSP_SSP0SR_BSY_BUSY|SSP_SSP0SR_RNE_NOTEMPTY)) != SSP_SSP0SR_RNE_NOTEMPTY);
+    /* clear the FIFO */
+    frame = SSP_SSP0DR;
+}
+
+#define CS 2,1
+#define SCK 2,11
+#define SDA 0,9
+#define RST 2,2
+
+uint8_t lcdRead(uint8_t data)
+{
+    uint32_t op211cache=IOCON_PIO2_11;
+    uint32_t op09cache=IOCON_PIO0_9;
+    uint32_t dircache=GPIO_GPIO2DIR;
+    IOCON_PIO2_11=IOCON_PIO2_11_FUNC_GPIO|IOCON_PIO2_11_MODE_PULLUP;
+    IOCON_PIO0_9=IOCON_PIO0_9_FUNC_GPIO|IOCON_PIO0_9_MODE_PULLUP;
+    gpioSetDir(SCK, 1);
+
+    uint8_t i;
+
+    gpioSetDir(SDA, 1);
+    gpioSetValue(SCK, 0);
+    gpioSetValue(CS, 0);
+    delayms(1);
+
+    gpioSetValue(SDA, 0);
+    gpioSetValue(SCK, 1);
+    delayms(1);
+    
+    for(i=0; i<8; i++){
+        gpioSetValue(SCK, 0);
+        delayms(1);
+        if( data & 0x80 )
+            gpioSetValue(SDA, 1);
+        else
+            gpioSetValue(SDA, 0);
+        data <<= 1;
+        gpioSetValue(SCK, 1);
+        delayms(1);
+    }
+    uint8_t ret = 0;
+
+    gpioSetDir(SDA, 0);
+    for(i=0; i<8; i++){
+        gpioSetValue(SCK, 0);
+        delayms(1);
+        ret <<= 1;
+        ret |= gpioGetValue(SDA);
+        gpioSetValue(SCK, 1);
+        delayms(1);
+    }
+    gpioSetValue(SCK, 0);
+
+    gpioSetValue(CS, 1);
+    gpioSetDir(SDA, 1);
+    IOCON_PIO2_11=op211cache;
+    IOCON_PIO0_9=op09cache;
+    GPIO_GPIO2DIR=dircache;
+    delayms(1);
+    return ret;
+}
+
+
+void lcdInit(void) {
+    int id;
+
+    sspInit(0, sspClockPolarity_Low, sspClockPhase_RisingEdge);
+
+    gpioSetValue(RB_LCD_CS, 1);
+    gpioSetValue(RB_LCD_RST, 1);
+
+    gpioSetDir(RB_LCD_CS, gpioDirection_Output);
+    gpioSetDir(RB_LCD_RST, gpioDirection_Output);
+
+    delayms(100);
+    gpioSetValue(RB_LCD_RST, 0);
+    delayms(100);
+    gpioSetValue(RB_LCD_RST, 1);
+    delayms(100);
+
+    id=lcdRead(220); // ID3
+    
+    if(id==14)
+        displayType=DISPLAY_N1600;
+    else /* ID3 == 48 */
+        displayType=DISPLAY_N1200;
+    
+/* Small Nokia 1200 LCD docs:
+ *           clear/ set
+ *  on       0xae / 0xaf
+ *  invert   0xa6 / 0xa7
+ *  mirror-x 0xA0 / 0xA1
+ *  mirror-y 0xc7 / 0xc8
+ *
+ *  0x20+x contrast (0=black - 0x2e)
+ *  0x40+x offset in rows from top (-0x7f)
+ *  0x80+x contrast? (0=black -0x9f?)
+ *  0xd0+x black lines from top? (-0xdf?)
+ *
+ */
+    lcd_select();
+
+    if(displayType==DISPLAY_N1200){
+       /* Decoded:
+        * E2: Internal reset
+        * AF: Display on/off: DON = 1
+        * A1: undefined?
+        * A4: all on/normal: DAL = 0
+        * 2F: charge pump on/off: PC = 1
+        * B0: set y address: Y[0-3] = 0
+        * 10: set x address (upper bits): X[6-4] = 0
+        */
+        static uint8_t initseq[]= { 0xE2,0xAF, // Display ON
+                             0xA1, // Mirror-X
+                             0xA4, 0x2F, 0xB0, 0x10};
+        int i = 0;
+        while(i<sizeof(initseq)){
+            lcdWrite(TYPE_CMD,initseq[i++]);
+            delayms(5); // actually only needed after the first
+        }
+    }else{ /* displayType==DISPLAY_N1600 */
+        static uint8_t initseq_d[] = {
+                       /* The controller is a PCF8833 -
+                   documentation can be found online.
+                        * CMD 01: Soft-reset
+                        * CMD 11: Sleep-out
+                        * CMD 29: Display ON
+                        * CMD 03: Booster voltage ON
+                        * CMD 13: Normal display mode
+                        * CMD 3A: interface pixel format 
+                        *   DAT 02  | 02:  8 bit/pixel (3:3:2)
+                        *           | 03: 12 bit/pixel (4:4:4)
+                        *           | 05: 16 bit/pixel (5:6:5)
+                        * CMD 2A: column address set
+                        *   DAT 1    : xs
+                        *   DAT 98-2 : xe
+                        * CMD 2B: page address set
+                        *   DAT 1    : ys
+                        *   DAT 70-2 : ye
+                        */
+            0x11, 
+            0x29, 
+            0x03, 
+            0x13, 
+            0x3A, px_INIT_MODE, 
+            0x2A, 1, 98-2, 
+            0x2B, 1, 70-2
+        };
+        uint16_t initseq_c = ~  (  /* comands: 1, data: 0 */
+                (1<<0) |
+                (1<<1) |
+                (1<<2) |
+                (1<<3) |
+                (1<<4) | (0<< 5) |
+                (1<<6) | (0<< 7) | (0<< 8) |
+                (1<<9) | (0<<10) | (0<<11) |
+                0);
+        int i = 0;
+
+        lcdWrite(0, 0x01); /* most color displays need the pause */
+        delayms(10);
+
+        while(i<sizeof(initseq_d)){
+            lcdWrite(initseq_c&1, initseq_d[i++]);
+            initseq_c = initseq_c >> 1;
+        }
+    }
+    lcd_deselect();
+}
+
+void lcdFill(char f){
+    memset(lcdBuffer,f,RESX*RESY_B);
+#if 0
+    int x;
+    for(x=0;x<RESX*RESY_B;x++) {
+        lcdBuffer[x]=f;
+    }
+#endif
+}
+
+void lcdSetPixel(char x, char y, bool f){
+    if (x<0 || x> RESX || y<0 || y > RESY)
+        return;
+    char y_byte = (RESY-(y+1)) / 8;
+    char y_off = (RESY-(y+1)) % 8;
+    char byte = lcdBuffer[y_byte*RESX+(RESX-(x+1))];
+    if (f) {
+        byte |= (1 << y_off);
+    } else {
+        byte &= ~(1 << y_off);
+    }
+    lcdBuffer[y_byte*RESX+(RESX-(x+1))] = byte;
+}
+
+bool lcdGetPixel(char x, char y){
+    char y_byte = (RESY-(y+1)) / 8;
+    char y_off = (RESY-(y+1)) % 8;
+    char byte = lcdBuffer[y_byte*RESX+(RESX-(x+1))];
+    return byte & (1 << y_off);
+}
+
+// Color display helper functions
+static inline void _helper_pixel8(uint8_t color1){
+    lcdWrite(TYPE_DATA, color1);
+}
+
+static void _helper_pixel12(uint16_t color){
+    static char odd=0;
+    static char rest;
+    if(odd){
+        lcdWrite(TYPE_DATA,(rest<<4) | (color>>8));
+        lcdWrite(TYPE_DATA,color&0xff);
+    }else{
+        lcdWrite(TYPE_DATA,(color>>4)&0xff);
+        rest=(color&0x0f);
+    };
+    odd=1-odd;
+}
+
+static void _helper_pixel16(uint16_t color){
+    lcdWrite(TYPE_DATA,color>>8);
+    lcdWrite(TYPE_DATA,color&0xFF);
+}
+
+#define COLORPACK_RGB565(r,g,b) (((r&0xF8) << 8) | ((g&0xFC)<<3) | ((b&0xF8) >> 3))
+#define COLORPACK_RGB444(r,g,b) ( ((r&0xF0)<<4) | (g&0xF0) | ((b&0xF0)>>4) )
+#define COLORPACK_RGB332(r,g,b) ( (((r>>5)&0x7)<<5) | (((g>>5)&0x7)<<2) | ((b>>6)&0x3) )
+
+static const px_type COLOR_FG =   px_PACK(0x00, 0x00, 0x00);
+static const px_type COLOR_BG =   px_PACK(0xff, 0xff, 0xff);
+
+void lcdDisplay(void) {
+    char byte;
+    lcd_select();
+
+    if(displayType==DISPLAY_N1200){
+      lcdWrite(TYPE_CMD,0xB0);
+      lcdWrite(TYPE_CMD,0x10);
+      lcdWrite(TYPE_CMD,0x00);
+      uint16_t i,page;
+      for(page=0; page<RESY_B;page++) {
+          for(i=0; i<RESX; i++) {
+              if (GLOBAL(lcdmirror))
+                  byte=lcdBuffer[page*RESX+RESX-1-(i)];
+              else
+                  byte=lcdBuffer[page*RESX+(i)];
+  
+              if (GLOBAL(lcdinvert))
+                  byte=~byte;
+      
+              lcdWrite(TYPE_DATA,byte);
+          }
+      }
+    } else { /* displayType==DISPLAY_N1600 */
+      uint16_t x,y;
+      bool px;
+      lcdWrite(TYPE_CMD,0x2C);
+  
+      for(y=RESY;y>0;y--){
+          for(x=RESX;x>0;x--){
+              if(GLOBAL(lcdmirror))
+                  px=lcdGetPixel(RESX-x,y-1);
+              else
+                  px=lcdGetPixel(x-1,y-1);
+
+             if((!px)^(!GLOBAL(lcdinvert))) {
+                     putpix(COLOR_FG); /* foreground */
+             } else {
+                     putpix(COLOR_BG); /* background */
+             }
+          }
+      }
+    };
+    lcd_deselect();
+}
+
+void lcdRefresh() __attribute__ ((weak, alias ("lcdDisplay")));
+
+inline void lcdInvert(void) {
+    GLOBAL(lcdinvert)=!GLOBAL(lcdinvert);
+}
+
+void lcdSetContrast(int c) {
+    lcd_select();
+    if(displayType==DISPLAY_N1200){
+        if(c<0x1F)
+            lcdWrite(TYPE_CMD,0x80+c);
+    }else{ /* displayType==DISPLAY_N1600 */
+        if(c<0x40) {
+            lcdWrite(TYPE_CMD,0x25);
+            lcdWrite(TYPE_DATA,4*c);
+        };
+    }
+    lcd_deselect();
+}
+
+void lcdSetInvert(int c) {
+    lcd_select();
+     /* it doesn't harm N1600, save space */
+//  if(displayType==DISPLAY_N1200)
+        lcdWrite(TYPE_CMD,(c&1)+0xa6);
+    lcd_deselect();
+}
+
+/* deprecated */
+void __attribute__((__deprecated__)) lcdToggleFlag(int flag) {
+    if(flag==LCD_MIRRORX)
+        GLOBAL(lcdmirror)=!GLOBAL(lcdmirror);
+    if(flag==LCD_INVERTED)
+        GLOBAL(lcdinvert)=!GLOBAL(lcdinvert);
+}
+
+void lcdShiftH(bool right, bool wrap) {
+       uint8_t tmp;
+       for (int yb = 0; yb<RESY_B; yb++) {
+               if (right) {
+                       tmp = lcdBuffer[yb*RESX];
+                       memmove(lcdBuffer + yb*RESX,lcdBuffer + yb*RESX+1 ,RESX-1);
+            lcdBuffer[yb*RESX+(RESX-1)] = wrap?tmp:0;
+               } else {
+                       tmp = lcdBuffer[yb*RESX+(RESX-1)];
+                       memmove(lcdBuffer + yb*RESX+1,lcdBuffer + yb*RESX ,RESX-1);
+                       lcdBuffer[yb*RESX] = wrap?tmp:0;
+               }
+       }
+}
+
+void lcdShiftV8(bool up, bool wrap) {
+       uint8_t tmp[RESX];
+       if (!up) {
+               if (wrap)
+            memmove(tmp, lcdBuffer, RESX);
+        else
+            memset(tmp,0,RESX);
+               memmove(lcdBuffer,lcdBuffer+RESX ,RESX*(RESY_B-1));
+               memmove(lcdBuffer+RESX*(RESY_B-1),tmp,RESX);
+       } else {
+               if (wrap)
+            memmove(tmp, lcdBuffer+RESX*(RESY_B-1), RESX);
+        else
+            memset(tmp,0,RESX);
+               memmove(lcdBuffer+RESX,lcdBuffer ,RESX*(RESY_B-1));
+               memmove(lcdBuffer,tmp,RESX);
+       }
+}
+
+void lcdShiftV(bool up, bool wrap) {
+       uint8_t tmp[RESX];
+       if (up) {
+               if (wrap) 
+            memmove(tmp,lcdBuffer+((RESY_B-1)*RESX),RESX);
+        else
+            memset(tmp,0,RESX);
+               for (int x = 0; x<RESX; x++){
+                       for (int y = RESY_B-1; y > 0; y--){
+                               lcdBuffer[x+(y*RESX)] = (lcdBuffer[x+(y*RESX)] << 1) |( lcdBuffer[x+((y-1)*RESX)] >> 7);
+                       }
+                       lcdBuffer[x] = ( lcdBuffer[x] << 1) | ((tmp[x]>>3)&1);
+               }
+                               
+       } else {
+               if (wrap)
+            memmove(tmp,lcdBuffer,RESX);
+        else
+            memset(tmp,0,RESX);
+               for (int x = 0; x<RESX; x++){
+                       for (int y = 0; y < (RESY_B-1); y++){
+                               lcdBuffer[x+(y*RESX)] = (lcdBuffer[x+(y*RESX)] >> 1) |( lcdBuffer[x+((y+1)*RESX)] << 7);
+                       }
+                       lcdBuffer[x+((RESY_B-1)*RESX)] = ( lcdBuffer[x+((RESY_B-1)*RESX)] >> 1) | ((tmp[x]<<3)&8);
+               }       
+       }
+}      
+
+void lcdShift(int x, int y, bool wrap) {
+       bool dir=true;
+
+    if(x<0){
+        dir=false;
+        x=-x;
+    };
+
+    while(x-->0)
+        lcdShiftH(dir, wrap);
+
+    if(y<0){
+        dir=false;
+        y=-y;
+    }else{
+        dir=true;
+    };
+
+    while(y>=8){
+        y-=8;
+        lcdShiftV8(dir, wrap);
+    };
+
+    while(y-->0)
+        lcdShiftV(dir, wrap);
+}
+
diff --git a/lcd/fonts/invaders.c b/lcd/fonts/invaders.c
new file mode 100644 (file)
index 0000000..687f8a8
--- /dev/null
@@ -0,0 +1,153 @@
+#include "invaders.h"
+
+/* Font data for Invaders */
+
+/* Space Invaders Pixel Art
+ */
+
+/* This file created by makefont.pl by Sec <sec@42.org> */
+
+/* Bitmaps */
+const uint8_t InvadersBitmaps[] = {
+ /* Char 65 is 11px wide @ 0 */
+  0x70,  /*  ***     */ 
+  0x18,  /*    **    */ 
+  0x7d,  /*  ***** * */ 
+  0xb6,  /* * ** **  */ 
+  0xbc,  /* * ****   */ 
+  0x3c,  /*   ****   */ 
+  0xbc,  /* * ****   */ 
+  0xb6,  /* * ** **  */ 
+  0x7d,  /*  ***** * */ 
+  0x18,  /*    **    */ 
+  0x70,  /*  ***     */ 
+
+
+ /* Char 66 is 12px wide @ 11 */
+  0x9c,  /* *  ***   */ 
+  0x9e,  /* *  ****  */ 
+  0x5e,  /*  * ****  */ 
+  0x76,  /*  *** **  */ 
+  0x37,  /*   ** *** */ 
+  0x5f,  /*  * ***** */ 
+  0x5f,  /*  * ***** */ 
+  0x37,  /*   ** *** */ 
+  0x76,  /*  *** **  */ 
+  0x5e,  /*  * ****  */ 
+  0x9e,  /* *  ****  */ 
+  0x9c,  /* *  ***   */ 
+
+
+ /* Char 67 is 8px wide @ 23 */
+  0x58,  /*  * **    */ 
+  0xbc,  /* * ****   */ 
+  0x16,  /*    * **  */ 
+  0x3f,  /*   ****** */ 
+  0x3f,  /*   ****** */ 
+  0x16,  /*    * **  */ 
+  0xbc,  /* * ****   */ 
+  0x58,  /*  * **    */ 
+
+
+ /* Char 80 is 7px wide @ 31 */
+  0xc0,  /* **       */ 
+  0xec,  /* *** **   */ 
+  0x7e,  /*  ******  */ 
+  0x3f,  /*   ****** */ 
+  0x7e,  /*  ******  */ 
+  0xec,  /* *** **   */ 
+  0xc0,  /* **       */ 
+
+
+ /* Char 85 is 16px wide @ 38 */
+  0x20,  /*   *     */ 
+  0x30,  /*   **    */ 
+  0x78,  /*  ****   */ 
+  0xec,  /* *** **  */ 
+  0x7c,  /*  *****  */ 
+  0x3c,  /*   ****  */ 
+  0x2e,  /*   * *** */ 
+  0x7e,  /*  ****** */ 
+  0x7e,  /*  ****** */ 
+  0x2e,  /*   * *** */ 
+  0x3c,  /*   ****  */ 
+  0x7c,  /*  *****  */ 
+  0xec,  /* *** **  */ 
+  0x78,  /*  ****   */ 
+  0x30,  /*   **    */ 
+  0x20,  /*   *     */ 
+
+
+ /* Char 97 is 11px wide @ 54 */
+  0x9e,  /* *  ****  */ 
+  0x38,  /*   ***    */ 
+  0x7d,  /*  ***** * */ 
+  0x36,  /*   ** **  */ 
+  0x3c,  /*   ****   */ 
+  0x3c,  /*   ****   */ 
+  0x3c,  /*   ****   */ 
+  0x36,  /*   ** **  */ 
+  0x7d,  /*  ***** * */ 
+  0x38,  /*   ***    */ 
+  0x9e,  /* *  ****  */ 
+
+
+ /* Char 98 is 12px wide @ 65 */
+  0x1c,  /*    ***   */ 
+  0x5e,  /*  * ****  */ 
+  0xfe,  /* *******  */ 
+  0xb6,  /* * ** **  */ 
+  0x37,  /*   ** *** */ 
+  0x5f,  /*  * ***** */ 
+  0x5f,  /*  * ***** */ 
+  0x37,  /*   ** *** */ 
+  0xb6,  /* * ** **  */ 
+  0xfe,  /* *******  */ 
+  0x5e,  /*  * ****  */ 
+  0x1c,  /*    ***   */ 
+
+
+ /* Char 99 is 8px wide @ 77 */
+  0x98,  /* *  **    */ 
+  0x5c,  /*  * ***   */ 
+  0xb6,  /* * ** **  */ 
+  0x5f,  /*  * ***** */ 
+  0x5f,  /*  * ***** */ 
+  0xb6,  /* * ** **  */ 
+  0x5c,  /*  * ***   */ 
+  0x98,  /* *  **    */ 
+
+
+};
+
+/* Character descriptors */
+const FONT_CHAR_INFO InvadersLengths[] = {
+ {11}, /* A */
+ {12}, /* B */
+ { 8}, /* C */
+ { 7}, /* P */
+ {16}, /* U */
+ {11}, /* a */
+ {12}, /* b */
+ { 8}, /* c */
+};
+
+const uint16_t InvadersExtra[] = {
+80,85,97,98,99,65535
+};
+
+/* Font info */
+const struct FONT_DEF Font_Invaders = {
+         0,   /* width (1 == compressed) */
+         8,   /* character height */
+        65,   /* first char */
+        67,   /* last char */
+    InvadersBitmaps, InvadersLengths, InvadersExtra
+};
+
+/* Font metadata: 
+ * Name:          Invaders
+ * Height:        8 px (1 bytes)
+ * Maximum width: 16 px
+ * Storage size:  93 bytes (uncompressed)
+ */
diff --git a/lcd/fonts/invaders.h b/lcd/fonts/invaders.h
new file mode 100644 (file)
index 0000000..395a238
--- /dev/null
@@ -0,0 +1,3 @@
+#include "lcd/fonts.h"
+
+extern const struct FONT_DEF Font_Invaders;
diff --git a/lcd/fonts/orbitron14.c b/lcd/fonts/orbitron14.c
new file mode 100644 (file)
index 0000000..e31b88b
--- /dev/null
@@ -0,0 +1,1767 @@
+#include "orbitron14.h"
+
+/* Font data for Orbitron Regular 14pt */
+
+/* Copyright (c) 2009, Matt McInerney <matt@pixelspread.com>
+ * 
+ * Copyright (c) 2009, Matt McInerney <matt@pixelspread.com>,
+ * with Reserved Font Name Orbitron.
+ * 
+ * This Font Software is licensed under the SIL Open Font License, Version 1.1.
+ * This license is copied below, and is also available with a FAQ at:
+ * http://scripts.sil.org/OFL
+ * 
+ * 
+ * -----------------------------------------------------------
+ * SIL OPEN FONT LICENSE Version 1.1 - 26 February 2007
+ * -----------------------------------------------------------
+ * 
+ * PREAMBLE
+ * The goals of the Open Font License (OFL) are to stimulate worldwide
+ * development of collaborative font projects, to support the font creation
+ * efforts of academic and linguistic communities, and to provide a free and
+ * open framework in which fonts may be shared and improved in partnership
+ * with others.
+ * 
+ * The OFL allows the licensed fonts to be used, studied, modified and
+ * redistributed freely as long as they are not sold by themselves. The
+ * fonts, including any derivative works, can be bundled, embedded, 
+ * redistributed and/or sold with any software provided that any reserved
+ * names are not used by derivative works. The fonts and derivatives,
+ * however, cannot be released under any other type of license. The
+ * requirement for fonts to remain under this license does not apply
+ * to any document created using the fonts or their derivatives.
+ * 
+ * DEFINITIONS
+ * "Font Software" refers to the set of files released by the Copyright
+ * Holder(s) under this license and clearly marked as such. This may
+ * include source files, build scripts and documentation.
+ * 
+ * "Reserved Font Name" refers to any names specified as such after the
+ * copyright statement(s).
+ * 
+ * "Original Version" refers to the collection of Font Software components as
+ * distributed by the Copyright Holder(s).
+ * 
+ * "Modified Version" refers to any derivative made by adding to, deleting,
+ * or substituting -- in part or in whole -- any of the components of the
+ * Original Version, by changing formats or by porting the Font Software to a
+ * new environment.
+ * 
+ * "Author" refers to any designer, engineer, programmer, technical
+ * writer or other person who contributed to the Font Software.
+ * 
+ * PERMISSION & CONDITIONS
+ * Permission is hereby granted, free of charge, to any person obtaining
+ * a copy of the Font Software, to use, study, copy, merge, embed, modify,
+ * redistribute, and sell modified and unmodified copies of the Font
+ * Software, subject to the following conditions:
+ * 
+ * 1) Neither the Font Software nor any of its individual components,
+ * in Original or Modified Versions, may be sold by itself.
+ * 
+ * 2) Original or Modified Versions of the Font Software may be bundled,
+ * redistributed and/or sold with any software, provided that each copy
+ * contains the above copyright notice and this license. These can be
+ * included either as stand-alone text files, human-readable headers or
+ * in the appropriate machine-readable metadata fields within text or
+ * binary files as long as those fields can be easily viewed by the user.
+ * 
+ * 3) No Modified Version of the Font Software may use the Reserved Font
+ * Name(s) unless explicit written permission is granted by the corresponding
+ * Copyright Holder. This restriction only applies to the primary font name as
+ * presented to the users.
+ * 
+ * 4) The name(s) of the Copyright Holder(s) or the Author(s) of the Font
+ * Software shall not be used to promote, endorse or advertise any
+ * Modified Version, except to acknowledge the contribution(s) of the
+ * Copyright Holder(s) and the Author(s) or with their explicit written
+ * permission.
+ * 
+ * 5) The Font Software, modified or unmodified, in part or in whole,
+ * must be distributed entirely under this license, and must not be
+ * distributed under any other license. The requirement for fonts to
+ * remain under this license does not apply to any document created
+ * using the Font Software.
+ * 
+ * TERMINATION
+ * This license becomes null and void if any of the above conditions are
+ * not met.
+ * 
+ * DISCLAIMER
+ * THE FONT SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO ANY WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT
+ * OF COPYRIGHT, PATENT, TRADEMARK, OR OTHER RIGHT. IN NO EVENT SHALL THE
+ * COPYRIGHT HOLDER BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
+ * INCLUDING ANY GENERAL, SPECIAL, INDIRECT, INCIDENTAL, OR CONSEQUENTIAL
+ * DAMAGES, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF THE USE OR INABILITY TO USE THE FONT SOFTWARE OR FROM
+ * OTHER DEALINGS IN THE FONT SOFTWARE.
+ * 
+ * See also: http://scripts.sil.org/OFL
+ * 
+ */
+
+/* This file created by makefont.pl by Sec <sec@42.org> */
+
+/* Bitmaps */
+const uint8_t Orbitron14ptBitmaps[] = {
+ /* Char 32 is 6px wide @ 0 */
+ /*                          */ 
+  0x08, 0x41, 
+
+ /* Char 33 is 5px wide @ 2 */
+ /*      **  **********      */ 
+ /*      *   **********      */ 
+  0x01, 0x12, 0x2a, 0xa1, 0x3a, 0x02, 0x91, 
+
+ /* Char 34 is 8px wide @ 9 */
+ /*                 ***      */ 
+ /*                 ***      */ 
+ /*                          */ 
+ /*                 ***      */ 
+ /*                 **       */ 
+  0x01, 0xcf, 0x30, 0x21, 0x3d, 0x82, 0x02, 0xa1, 
+
+
+ /* Char 35 is 15px wide @ 17 */
+ /*         **    *          */ 
+ /*      *****    **         */ 
+ /*       *****   **         */ 
+ /*         ********         */ 
+ /*         **   *****       */ 
+ /*         **    *****      */ 
+ /*         **    **         */ 
+ /*      ** **    **         */ 
+ /*      *****    **         */ 
+ /*         ***** **         */ 
+ /*         ** *****         */ 
+ /*         **    *****      */ 
+ /*         **    ** **      */ 
+ /*               *          */ 
+  0x01, 0x42, 0x41, 0xd1, 0x54, 0x2d, 0x15, 0x32, 
+  0xd3, 0x8d, 0x32, 0x35, 0xd1, 0x24, 0x5d, 0x02, 
+  0x42, 0xd0, 0x21, 0x24, 0x2d, 0x05, 0x42, 0xd3, 
+  0x51, 0x2d, 0x32, 0x15, 0xd3, 0x24, 0x5d, 0x02, 
+  0x42, 0x12, 0xd6, 0x19, 
+
+ /* Char 36 is 15px wide @ 53 */
+ /*       **    ******       */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*    ******************    */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*       ******    **       */ 
+ /*        ***               */ 
+  0x01, 0x22, 0x46, 0xbe, 0x32, 0x42, 0x42, 0x8d, 
+  0x58, 0xe3, 0x24, 0x24, 0x2b, 0x64, 0x2d, 0x03, 
+  0xd1, 
+
+ /* Char 37 is 18px wide @ 70 */
+ /*              *****       */ 
+ /*              *   *       */ 
+ /*       **    **   **      */ 
+ /*        **   **   **      */ 
+ /*        ***   *   **      */ 
+ /*         **   *****       */ 
+ /*          **              */ 
+ /*           **             */ 
+ /*            **            */ 
+ /*             **           */ 
+ /*        ***  ***          */ 
+ /*      ******  **          */ 
+ /*      *    *   **         */ 
+ /*      *    *    **        */ 
+ /*      *    *     **       */ 
+ /*      ******      *       */ 
+ /*        ***               */ 
+  0x01, 0x95, 0xd6, 0x13, 0x1c, 0x24, 0x23, 0x2c, 
+  0x23, 0x23, 0x2c, 0x33, 0x13, 0x2d, 0x02, 0x35, 
+  0xd2, 0x2d, 0xa2, 0xda, 0x2d, 0xa2, 0xd4, 0x32, 
+  0x3d, 0x16, 0x22, 0xd1, 0x14, 0x13, 0x2d, 0x01, 
+  0x41, 0x42, 0xc1, 0x41, 0x52, 0xb6, 0x61, 0xd0, 
+  0x3d, 0x11, 
+
+ /* Char 38 is 18px wide @ 112 */
+ /*       ******             */ 
+ /*      *************       */ 
+ /*      **     **  **       */ 
+ /*      **     *    **      */ 
+ /*      **    **    **      */ 
+ /*      **    *     **      */ 
+ /*      **   **     **      */ 
+ /*      **   *      **      */ 
+ /*      **  **      **      */ 
+ /*      **  *       **      */ 
+ /*      ** **       **      */ 
+ /*      ** *       **       */ 
+ /*      ******     **       */ 
+ /*       *****              */ 
+ /*       **                 */ 
+ /*       *                  */ 
+  0x01, 0x26, 0xd4, 0xd0, 0xb2, 0x52, 0x22, 0xb2, 
+  0x51, 0x42, 0xa2, 0x42, 0x42, 0xa2, 0x41, 0x52, 
+  0xa2, 0x32, 0x52, 0xa2, 0x31, 0x62, 0xa2, 0x22, 
+  0x62, 0xa2, 0x21, 0x72, 0xa2, 0x12, 0x72, 0xa2, 
+  0x11, 0x72, 0xb6, 0x52, 0xc5, 0xd6, 0x2d, 0x91, 
+  0x01, 0xd1, 
+
+ /* Char 39 is 5px wide @ 154 */
+ /*                 ***      */ 
+ /*                 ***      */ 
+  0x01, 0xcf, 0x30, 0x29, 
+
+ /* Char 40 is 6px wide @ 158 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **          **      */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0x2a, 0x20, 0x29, 
+
+ /* Char 41 is 6px wide @ 165 */
+ /*      **          **      */ 
+ /*      *************       */ 
+ /*       ***********        */ 
+  0x01, 0x12, 0xa2, 0xad, 0x0c, 0xb0, 0x2b, 
+
+ /* Char 42 is 10px wide @ 172 */
+ /*                **        */ 
+ /*            ** **         */ 
+ /*             ****         */ 
+ /*              ******      */ 
+ /*             ****         */ 
+ /*            ** **         */ 
+ /*                **        */ 
+  0x01, 0xb2, 0xd5, 0x21, 0x2d, 0x74, 0xd8, 0x6d, 
+  0x44, 0xd6, 0x21, 0x2d, 0xa2, 0x02, 0xb1, 
+
+ /* Char 43 is 9px wide @ 187 */
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*        *******           */ 
+ /*        *******           */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+  0xae, 0x11, 0xd7, 0xf7, 0xd7, 0xe1, 0x10, 0x19, 
+
+
+ /* Char 44 is 4px wide @ 195 */
+ /*    ****                  */ 
+ /*     **                   */ 
+  0xde, 0x4d, 0x82, 0x01, 0xe1, 
+
+ /* Char 45 is 10px wide @ 200 */
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+  0x01, 0x6e, 0x61, 0x01, 0x91, 
+
+ /* Char 46 is 4px wide @ 205 */
+ /*      **                  */ 
+ /*      *                   */ 
+  0x01, 0x12, 0xd9, 0x10, 0x1e, 
+
+ /* Char 47 is 10px wide @ 210 */
+ /*       **                 */ 
+ /*        **                */ 
+ /*         **               */ 
+ /*          **              */ 
+ /*           **             */ 
+ /*            ***           */ 
+ /*              **          */ 
+ /*               **         */ 
+ /*                **        */ 
+ /*                 **       */ 
+  0x62, 0xda, 0x2d, 0xa2, 0xda, 0x2d, 0xa2, 0xda, 
+  0x3d, 0xa2, 0xda, 0x2d, 0xa2, 0xda, 0x26, 
+
+ /* Char 48 is 16px wide @ 225 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      ****        **      */ 
+ /*      ** **       **      */ 
+ /*      **  **      **      */ 
+ /*      **   **     **      */ 
+ /*      **   ***    **      */ 
+ /*      **    **    **      */ 
+ /*      **     **   **      */ 
+ /*      **      **  **      */ 
+ /*      **       ** **      */ 
+ /*      **       *****      */ 
+ /*      *************       */ 
+ /*       ***********        */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0x48, 0x2a, 0x21, 0x27, 
+  0x2a, 0x22, 0x26, 0x2a, 0x23, 0x25, 0x2a, 0x23, 
+  0x34, 0x2a, 0x24, 0x24, 0x2a, 0x25, 0x23, 0x2a, 
+  0x26, 0x22, 0x2a, 0x27, 0x21, 0x2a, 0x27, 0x5a, 
+  0xd0, 0xcb, 0x01, 0x31, 
+
+ /* Char 49 is 8px wide @ 261 */
+ /*               **         */ 
+ /*                **        */ 
+ /*                 ***      */ 
+ /*      **************      */ 
+ /*      **************      */ 
+  0x01, 0xa2, 0xda, 0x2d, 0xa3, 0xaf, 0xd1, 0x02, 
+  0x91, 
+
+ /* Char 50 is 16px wide @ 270 */
+ /*      ******     **       */ 
+ /*      *******    **       */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    **    **      */ 
+ /*      **    *******       */ 
+ /*      **     *****        */ 
+  0x01, 0x16, 0x52, 0xb7, 0x42, 0xbe, 0x72, 0x41, 
+  0x52, 0xa2, 0x42, 0x42, 0xa2, 0x47, 0xb2, 0x55, 
+  0x01, 0x31, 
+
+ /* Char 51 is 16px wide @ 288 */
+ /*       **        **       */ 
+ /*      **         **       */ 
+ /*      **          **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      *************       */ 
+ /*       *****              */ 
+  0x01, 0x22, 0x82, 0xb2, 0x92, 0xb2, 0xa2, 0xae, 
+  0x72, 0x42, 0x42, 0xad, 0x0c, 0x50, 0x19, 
+
+ /* Char 52 is 14px wide @ 303 */
+ /*          **              */ 
+ /*         ****             */ 
+ /*         ****             */ 
+ /*         ** **            */ 
+ /*         **  **           */ 
+ /*         **   **          */ 
+ /*         **    **         */ 
+ /*         **    ***        */ 
+ /*         **     ***       */ 
+ /*         **      ***      */ 
+ /*      **************      */ 
+ /*         **               */ 
+ /*         **               */ 
+  0x92, 0xd8, 0xf4, 0xd7, 0x21, 0x2d, 0x62, 0x22, 
+  0xd5, 0x23, 0x2d, 0x42, 0x42, 0xd3, 0x24, 0x3d, 
+  0x22, 0x53, 0xd1, 0x26, 0x3a, 0xd1, 0xd0, 0xf2, 
+  0x01, 0xa1, 
+
+ /* Char 53 is 16px wide @ 329 */
+ /*       **   ********      */ 
+ /*      ***   ********      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      ********    **      */ 
+ /*       ******     **      */ 
+  0x01, 0x22, 0x38, 0xa3, 0x38, 0xae, 0x82, 0x42, 
+  0x42, 0xa8, 0x42, 0xb6, 0x52, 0x01, 0x11, 
+
+ /* Char 54 is 16px wide @ 344 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    *       */ 
+ /*      ********            */ 
+ /*       ******             */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0xe7, 0x24, 0x24, 0x2a, 
+  0x24, 0x24, 0x1b, 0x8d, 0x46, 0x01, 0x81, 
+
+ /* Char 55 is 13px wide @ 359 */
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*      *************       */ 
+ /*      ***********         */ 
+  0xd4, 0xe8, 0x2a, 0xd0, 0xbb, 0x01, 0x41, 
+
+ /* Char 56 is 16px wide @ 366 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      *************       */ 
+ /*       ***********        */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0xe8, 0x24, 0x24, 0x2a, 
+  0xd0, 0xcb, 0x01, 0x31, 
+
+ /* Char 57 is 16px wide @ 378 */
+ /*             ******       */ 
+ /*      **    *******       */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      *************       */ 
+ /*       ***********        */ 
+  0x01, 0x86, 0xb2, 0x47, 0xbe, 0x82, 0x41, 0x52, 
+  0xad, 0x0c, 0xb0, 0x13, 
+
+ /* Char 58 is 4px wide @ 390 */
+ /*      **        *         */ 
+ /*      *         *         */ 
+  0x01, 0x12, 0x81, 0xd0, 0x19, 0x10, 0x14, 
+
+ /* Char 59 is 4px wide @ 397 */
+ /*    ****        *         */ 
+ /*     **         *         */ 
+  0xde, 0x48, 0x1c, 0x29, 0x10, 0x14, 
+
+ /* Char 60 is 9px wide @ 403 */
+ /*          ***             */ 
+ /*          ***             */ 
+ /*         ** **            */ 
+ /*         **  **           */ 
+ /*        **   **           */ 
+ /*        *     **          */ 
+ /*       **     **          */ 
+ /*       *       **         */ 
+  0x9f, 0x3d, 0x72, 0x12, 0xd6, 0x22, 0x2d, 0x42, 
+  0x32, 0xd4, 0x15, 0x2d, 0x22, 0x52, 0xd2, 0x17, 
+  0x20, 0x14, 
+
+ /* Char 61 is 12px wide @ 421 */
+ /*         *   *            */ 
+ /*         *   *            */ 
+ /*         *   *            */ 
+ /*         *   *            */ 
+ /*         *   *            */ 
+ /*         *   *            */ 
+ /*         *   *            */ 
+ /*         *   *            */ 
+ /*         *   *            */ 
+ /*         *   *            */ 
+  0x01, 0x4e, 0x81, 0x31, 0x01, 0x71, 
+
+ /* Char 62 is 10px wide @ 427 */
+ /*       *       **         */ 
+ /*       **     **          */ 
+ /*        **    **          */ 
+ /*        **   **           */ 
+ /*         **  *            */ 
+ /*         ** **            */ 
+ /*          ***             */ 
+ /*           **             */ 
+  0x01, 0x21, 0x72, 0xd1, 0x25, 0x2d, 0x32, 0x42, 
+  0xd3, 0x23, 0x2d, 0x52, 0x21, 0xd6, 0x21, 0x2d, 
+  0x73, 0xd9, 0x20, 0x18, 
+
+ /* Char 63 is 13px wide @ 447 */
+ /*                  **      */ 
+ /*                  **      */ 
+ /*      **  **      **      */ 
+ /*      *   ***     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*            *******       */ 
+ /*             *****        */ 
+  0x01, 0xdf, 0x2a, 0x22, 0x26, 0x2a, 0x13, 0x35, 
+  0x2d, 0x2e, 0x42, 0x52, 0xd3, 0x7d, 0x55, 0x71, 
+
+
+ /* Char 64 is 16px wide @ 463 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **  *****   **      */ 
+ /*      **  *    *  **      */ 
+ /*      **  *    *  **      */ 
+ /*      **  *    *  **      */ 
+ /*      **  *    *  **      */ 
+ /*      **  *****   **      */ 
+ /*      **  *       **      */ 
+ /*      **  *       **      */ 
+ /*      **  *********       */ 
+ /*      **  ********        */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0xf2, 0xa2, 0xa2, 0x25, 
+  0x32, 0xae, 0x22, 0x21, 0x41, 0x22, 0xa2, 0x25, 
+  0x32, 0xaf, 0x22, 0x17, 0x2a, 0x22, 0x9b, 0x22, 
+  0x80, 0x13, 
+
+ /* Char 65 is 16px wide @ 489 */
+ /*      *************       */ 
+ /*      *************       */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*      *************       */ 
+ /*      ************        */ 
+  0x01, 0x1f, 0xd0, 0xd3, 0xe8, 0x25, 0x2a, 0xd0, 
+  0xbc, 0x01, 0x31, 
+
+ /* Char 66 is 16px wide @ 500 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      *************       */ 
+ /*       *****              */ 
+  0x01, 0x1f, 0xd1, 0xae, 0x82, 0x42, 0x42, 0xad, 
+  0x0c, 0x50, 0x19, 
+
+ /* Char 67 is 16px wide @ 511 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      *           **      */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0xe9, 0x2a, 0x2a, 0x1b, 
+  0x20, 0x11, 
+
+ /* Char 68 is 16px wide @ 521 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      *************       */ 
+ /*       ***********        */ 
+  0x01, 0x1f, 0xd1, 0xae, 0x82, 0xa2, 0xad, 0x0c, 
+  0xb0, 0x13, 
+
+ /* Char 69 is 15px wide @ 531 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      *           *       */ 
+  0x01, 0x1f, 0xd1, 0xae, 0x62, 0x42, 0x42, 0xaf, 
+  0x2a, 0x2a, 0x1b, 0x10, 0x12, 
+
+ /* Char 70 is 14px wide @ 544 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*            **    **      */ 
+ /*            **    **      */ 
+ /*            **    **      */ 
+ /*            **    **      */ 
+ /*            **    **      */ 
+ /*            **    **      */ 
+ /*            **    **      */ 
+ /*            **    **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  *       */ 
+  0x01, 0x1f, 0xd1, 0xd3, 0xe6, 0x24, 0x2d, 0x9f, 
+  0x2d, 0x91, 0x61, 
+
+ /* Char 71 is 16px wide @ 555 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      **    *     **      */ 
+ /*      *******    **       */ 
+ /*        *****    *        */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0xe5, 0x2a, 0x2a, 0xe1, 
+  0x24, 0x15, 0x2a, 0x74, 0x2d, 0x05, 0x41, 0x01, 
+  0x31, 
+
+ /* Char 72 is 16px wide @ 572 */
+ /*      **************      */ 
+ /*      *************       */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*      *************       */ 
+ /*      **************      */ 
+  0x01, 0x1d, 0x1a, 0xd0, 0xd4, 0xe8, 0x2d, 0x3d, 
+  0x0b, 0xd1, 0x01, 0x11, 
+
+ /* Char 73 is 5px wide @ 584 */
+ /*      **************      */ 
+ /*      *************       */ 
+  0x01, 0x1d, 0x1a, 0xd0, 0x02, 0xa1, 
+
+ /* Char 74 is 15px wide @ 590 */
+ /*       **                 */ 
+ /*      ***                 */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **************      */ 
+ /*        ************      */ 
+  0x62, 0xd8, 0x3d, 0x8e, 0x82, 0xd9, 0xd1, 0xcc, 
+  0x01, 0x11, 
+
+ /* Char 75 is 15px wide @ 600 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*            **            */ 
+ /*           ***            */ 
+ /*          *****           */ 
+ /*         ***  ***         */ 
+ /*        **     ***        */ 
+ /*       **       ***       */ 
+ /*      **          **      */ 
+ /*      *            *      */ 
+  0x01, 0x1f, 0xd1, 0xd3, 0xe2, 0x2d, 0x83, 0xd7, 
+  0x5d, 0x53, 0x23, 0xd2, 0x25, 0x3d, 0x02, 0x73, 
+  0xb2, 0xa2, 0xa1, 0xc1, 0x01, 0x11, 
+
+ /* Char 76 is 15px wide @ 622 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      *                   */ 
+  0x01, 0x1f, 0xd1, 0xae, 0x92, 0xd9, 0x1d, 0x51, 
+
+
+ /* Char 77 is 18px wide @ 630 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*                 **       */ 
+ /*                **        */ 
+ /*              ***         */ 
+ /*             ***          */ 
+ /*            ***           */ 
+ /*           **             */ 
+ /*           ***            */ 
+ /*            ***           */ 
+ /*              **          */ 
+ /*               **         */ 
+ /*                ***       */ 
+ /*                 ***      */ 
+ /*      **************      */ 
+ /*      **************      */ 
+  0x01, 0x1f, 0xd1, 0xd8, 0x2d, 0x82, 0xd7, 0x3d, 
+  0x73, 0xd7, 0x3d, 0x72, 0xd9, 0x3d, 0x93, 0xda, 
+  0x2d, 0xa2, 0xda, 0x3d, 0x93, 0xaf, 0xd1, 0x01, 
+  0x11, 
+
+ /* Char 78 is 16px wide @ 655 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*                 **       */ 
+ /*                **        */ 
+ /*              ***         */ 
+ /*             ***          */ 
+ /*            ***           */ 
+ /*           **             */ 
+ /*          **              */ 
+ /*        ***               */ 
+ /*       ***                */ 
+ /*      ***                 */ 
+ /*      **************      */ 
+ /*      **************      */ 
+  0x01, 0x1f, 0xd1, 0xd8, 0x2d, 0x82, 0xd7, 0x3d, 
+  0x73, 0xd7, 0x3d, 0x72, 0xd8, 0x2d, 0x73, 0xd7, 
+  0x3d, 0x73, 0xd8, 0xfd, 0x10, 0x11, 
+
+ /* Char 79 is 16px wide @ 677 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      *************       */ 
+ /*        **********        */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0xe8, 0x2a, 0x2a, 0xd0, 
+  0xd0, 0xa0, 0x13, 
+
+ /* Char 80 is 15px wide @ 688 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           ********       */ 
+ /*             *****        */ 
+  0x01, 0x1f, 0xd1, 0xd2, 0xe8, 0x25, 0x2d, 0x28, 
+  0xd5, 0x57, 
+
+ /* Char 81 is 17px wide @ 698 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      *************       */ 
+ /*      ************        */ 
+ /*      **                  */ 
+ /*      *                   */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0xe8, 0x2a, 0x2a, 0xd0, 
+  0xbc, 0xc2, 0xd9, 0x1d, 0x51, 
+
+ /* Char 82 is 16px wide @ 711 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*          ***     **      */ 
+ /*        *****     **      */ 
+ /*       *** **     **      */ 
+ /*      ***  **     **      */ 
+ /*      *    ********       */ 
+ /*             *****        */ 
+  0x01, 0x1f, 0xd1, 0xd2, 0xe4, 0x25, 0x2d, 0x13, 
+  0x52, 0xc5, 0x52, 0xb3, 0x12, 0x52, 0xa3, 0x22, 
+  0x52, 0xa1, 0x48, 0xd5, 0x50, 0x13, 
+
+ /* Char 83 is 16px wide @ 733 */
+ /*       **    ******       */ 
+ /*      **    *******       */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      *******    **       */ 
+ /*        ****     *        */ 
+  0x01, 0x22, 0x46, 0xb2, 0x47, 0xbe, 0x82, 0x42, 
+  0x42, 0xa7, 0x42, 0xd0, 0x45, 0x10, 0x13, 
+
+ /* Char 84 is 15px wide @ 748 */
+ /*                  *       */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*      **************      */ 
+ /*      **************      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+  0xd4, 0x1d, 0xae, 0x32, 0xaf, 0xd1, 0xd9, 0xe4, 
+  0x20, 0x11, 
+
+ /* Char 85 is 16px wide @ 758 */
+ /*       *************      */ 
+ /*      *************       */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **************      */ 
+ /*        ************      */ 
+  0x01, 0x2d, 0x0a, 0xd0, 0xbe, 0x82, 0xd9, 0xd1, 
+  0xcc, 0x01, 0x11, 
+
+ /* Char 86 is 19px wide @ 769 */
+ /*                  **      */ 
+ /*                ****      */ 
+ /*               ***        */ 
+ /*             ***          */ 
+ /*           ****           */ 
+ /*          ***             */ 
+ /*        ***               */ 
+ /*      ***                 */ 
+ /*      **                  */ 
+ /*      ***                 */ 
+ /*        ***               */ 
+ /*          ***             */ 
+ /*           ****           */ 
+ /*             ***          */ 
+ /*               ***        */ 
+ /*                ****      */ 
+ /*                  **      */ 
+  0x01, 0xd2, 0xd7, 0x4d, 0x63, 0xd6, 0x3d, 0x64, 
+  0xd6, 0x3d, 0x63, 0xd6, 0x3d, 0x82, 0xd9, 0x3d, 
+  0xa3, 0xda, 0x3d, 0x94, 0xd9, 0x3d, 0xa3, 0xd9, 
+  0x4d, 0x92, 0x01, 0x11, 
+
+ /* Char 87 is 22px wide @ 797 */
+ /*                 ***      */ 
+ /*              *****       */ 
+ /*            *****         */ 
+ /*         *****            */ 
+ /*      *****               */ 
+ /*      ****                */ 
+ /*       *****              */ 
+ /*          *****           */ 
+ /*             *****        */ 
+ /*                ****      */ 
+ /*                 ***      */ 
+ /*              *****       */ 
+ /*           *****          */ 
+ /*         ****             */ 
+ /*      *****               */ 
+ /*      ****                */ 
+ /*        *****             */ 
+ /*          *****           */ 
+ /*             *****        */ 
+ /*                ****      */ 
+ /*                   *      */ 
+  0x01, 0xc3, 0xd5, 0x5d, 0x45, 0xd3, 0x5d, 0x35, 
+  0xd6, 0x4d, 0x85, 0xd9, 0x5d, 0x95, 0xd9, 0x4d, 
+  0x83, 0xd5, 0x5d, 0x35, 0xd4, 0x4d, 0x45, 0xd6, 
+  0x4d, 0x95, 0xd8, 0x5d, 0x95, 0xd9, 0x4d, 0xa1, 
+  0x51, 
+
+ /* Char 88 is 16px wide @ 830 */
+ /*      *            *      */ 
+ /*      **          **      */ 
+ /*       **       ***       */ 
+ /*        **     ***        */ 
+ /*         ***  ***         */ 
+ /*          *****           */ 
+ /*           ***            */ 
+ /*           ****           */ 
+ /*         ***  **          */ 
+ /*        ***    ***        */ 
+ /*       **       ***       */ 
+ /*      **         ***      */ 
+ /*      *            *      */ 
+  0x01, 0x11, 0xc1, 0xa2, 0xa2, 0xb2, 0x73, 0xd0, 
+  0x25, 0x3d, 0x23, 0x23, 0xd4, 0x5d, 0x73, 0xd8, 
+  0x4d, 0x53, 0x22, 0xd3, 0x34, 0x3d, 0x02, 0x73, 
+  0xb2, 0x93, 0xa1, 0xc1, 0x02, 0x91, 
+
+ /* Char 89 is 16px wide @ 860 */
+ /*                  **      */ 
+ /*                 **       */ 
+ /*               ***        */ 
+ /*              ***         */ 
+ /*             **           */ 
+ /*           ***            */ 
+ /*      *******             */ 
+ /*            **            */ 
+ /*             ***          */ 
+ /*              ***         */ 
+ /*                **        */ 
+ /*                 **       */ 
+ /*                  **      */ 
+  0x01, 0xd2, 0xd8, 0x2d, 0x73, 0xd7, 0x3d, 0x72, 
+  0xd7, 0x3d, 0x37, 0xda, 0x2d, 0xa3, 0xd9, 0x3d, 
+  0xa2, 0xda, 0x2d, 0xa2, 0x02, 0x91, 
+
+ /* Char 90 is 16px wide @ 882 */
+ /*      ***         **      */ 
+ /*      ***         **      */ 
+ /*      ****        **      */ 
+ /*      ** **       **      */ 
+ /*      **  **      **      */ 
+ /*      **   **     **      */ 
+ /*      **   ***    **      */ 
+ /*      **    ***   **      */ 
+ /*      **     **   **      */ 
+ /*      **      **  **      */ 
+ /*      **       ** **      */ 
+ /*      **        ****      */ 
+ /*      **         ***      */ 
+ /*      *          ***      */ 
+  0x01, 0x1f, 0x39, 0x2a, 0x48, 0x2a, 0x21, 0x27, 
+  0x2a, 0x22, 0x26, 0x2a, 0x23, 0x25, 0x2a, 0x23, 
+  0x34, 0x2a, 0x24, 0x33, 0x2a, 0x25, 0x23, 0x2a, 
+  0x26, 0x22, 0x2a, 0x27, 0x21, 0x2a, 0x28, 0x4a, 
+  0x29, 0x3a, 0x1a, 0x30, 0x11, 
+
+ /* Char 91 is 6px wide @ 919 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*      **          **      */ 
+  0x01, 0x1f, 0xd1, 0xa2, 0xa2, 0x02, 0x91, 
+
+ /* Char 92 is 10px wide @ 926 */
+ /*                 **       */ 
+ /*                **        */ 
+ /*               **         */ 
+ /*              **          */ 
+ /*            **            */ 
+ /*           **             */ 
+ /*          **              */ 
+ /*         **               */ 
+ /*       ***                */ 
+ /*       *                  */ 
+  0xd3, 0x2d, 0x82, 0xd8, 0x2d, 0x82, 0xd7, 0x2d, 
+  0x82, 0xd8, 0x2d, 0x82, 0xd7, 0x3d, 0x81, 0xd4, 
+
+
+ /* Char 93 is 6px wide @ 942 */
+ /*      **          **      */ 
+ /*      **************      */ 
+ /*      **************      */ 
+  0x01, 0x12, 0xa2, 0xaf, 0xd1, 0x02, 0x91, 
+
+ /* Char 94 is 1px wide @ 949 */
+ /*                          */ 
+  0xdb, 
+
+ /* Char 95 is 16px wide @ 950 */
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+ /*    **                    */ 
+  0xde, 0xec, 0x20, 0x1f, 
+
+ /* Char 96 is 4px wide @ 954 */
+ /*                       ** */ 
+ /*                       *  */ 
+  0x02, 0x22, 0xd9, 0x1d, 0xc1, 
+
+ /* Char 97 is 13px wide @ 959 */
+ /*       *****   **         */ 
+ /*      ******   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **  ***  **         */ 
+ /*      **********          */ 
+  0x01, 0x25, 0x32, 0xd0, 0x63, 0x2d, 0x0e, 0x52, 
+  0x31, 0x32, 0xd0, 0x22, 0x32, 0x2d, 0x0a, 0x01, 
+  0x51, 
+
+ /* Char 98 is 13px wide @ 976 */
+ /*      ***************     */ 
+ /*      **************      */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*       *********          */ 
+  0x01, 0x1d, 0x29, 0xd1, 0xae, 0x62, 0x72, 0xd1, 
+  0x90, 0x15, 
+
+ /* Char 99 is 13px wide @ 986 */
+ /*       *********          */ 
+ /*      ***********         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+  0x01, 0x29, 0xd1, 0xbd, 0x0e, 0x72, 0x72, 0x01, 
+  0x41, 
+
+ /* Char 100 is 13px wide @ 995 */
+ /*        *******           */ 
+ /*      ***********         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      ***************     */ 
+ /*      **************      */ 
+  0x77, 0xd2, 0xbd, 0x0e, 0x62, 0x72, 0xd0, 0xd2, 
+  0x9d, 0x10, 0x11, 
+
+ /* Char 101 is 13px wide @ 1006 */
+ /*       *********          */ 
+ /*      ***********         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   **  **         */ 
+ /*      **   *****          */ 
+  0x01, 0x29, 0xd1, 0xbd, 0x0e, 0x52, 0x31, 0x32, 
+  0xd0, 0x23, 0x22, 0x2d, 0x02, 0x35, 0x01, 0x51, 
+
+
+ /* Char 102 is 8px wide @ 1022 */
+ /*      **************      */ 
+ /*      **************      */ 
+ /*               **  **     */ 
+ /*               **  **     */ 
+ /*               **  **     */ 
+ /*               **  **     */ 
+  0x01, 0x1f, 0xd1, 0xd6, 0xe2, 0x22, 0x2d, 0xf1, 
+
+
+ /* Char 103 is 13px wide @ 1030 */
+ /*       *********          */ 
+ /*      **       **         */ 
+ /*  *   **       **         */ 
+ /*  *   **       **         */ 
+ /*  *   **       **         */ 
+ /*  *   **       **         */ 
+ /*  *   **       **         */ 
+ /*  *   **       **         */ 
+ /*  *   **       **         */ 
+ /*  ***************         */ 
+ /*   *************          */ 
+  0x01, 0x29, 0xd1, 0x27, 0x29, 0xe5, 0x13, 0x27, 
+  0x29, 0xd2, 0xad, 0x00, 0x15, 
+
+ /* Char 104 is 13px wide @ 1043 */
+ /*      ***************     */ 
+ /*      **************      */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*      **********          */ 
+  0x01, 0x1d, 0x29, 0xd1, 0xd6, 0xe6, 0x2d, 0x0a, 
+  0x01, 0x51, 
+
+ /* Char 105 is 4px wide @ 1053 */
+ /*      ***********  **     */ 
+ /*      ***********  *      */ 
+  0x01, 0x1b, 0x22, 0x9b, 0x21, 0x01, 0x11, 
+
+ /* Char 106 is 5px wide @ 1060 */
+ /* **                       */ 
+ /* **                       */ 
+ /*  ***************  **     */ 
+  0xe2, 0xfd, 0xad, 0x22, 0x20, 0x28, 
+
+ /* Char 107 is 12px wide @ 1066 */
+ /*      ***************     */ 
+ /*      **************      */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*          ***             */ 
+ /*         ** **            */ 
+ /*        **   **           */ 
+ /*      ***     ***         */ 
+ /*      **       **         */ 
+ /*      *         *         */ 
+  0x01, 0x1d, 0x29, 0xd1, 0xd2, 0xe1, 0x1d, 0x93, 
+  0xd7, 0x21, 0x2d, 0x52, 0x32, 0xd2, 0x35, 0x3d, 
+  0x02, 0x72, 0xd0, 0x19, 0x18, 
+
+ /* Char 108 is 6px wide @ 1087 */
+ /*       **************     */ 
+ /*      **************      */ 
+ /*      **                  */ 
+ /*      **                  */ 
+  0x01, 0x2d, 0x19, 0xd1, 0xaf, 0x20, 0x1d, 
+
+ /* Char 109 is 19px wide @ 1094 */
+ /*      ***********         */ 
+ /*      ***********         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*      ***********         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*      ***********         */ 
+ /*      **********          */ 
+  0x01, 0x1f, 0xbd, 0x9e, 0x42, 0xd0, 0xbd, 0x9e, 
+  0x42, 0xd0, 0xbd, 0x0a, 0x01, 0x51, 
+
+ /* Char 110 is 13px wide @ 1108 */
+ /*      ***********         */ 
+ /*      ***********         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*      **********          */ 
+  0x01, 0x1f, 0xbd, 0x9e, 0x62, 0xd0, 0xa0, 0x15, 
+
+
+ /* Char 111 is 13px wide @ 1116 */
+ /*       *********          */ 
+ /*      ***********         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*       *********          */ 
+  0x01, 0x29, 0xd1, 0xbd, 0x0e, 0x62, 0x72, 0xd1, 
+  0x90, 0x15, 
+
+ /* Char 112 is 13px wide @ 1126 */
+ /*  ***************         */ 
+ /*  ***************         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*       *********          */ 
+  0xdc, 0xfd, 0x2d, 0x0e, 0x62, 0x72, 0xd1, 0x90, 
+  0x15, 
+
+ /* Char 113 is 13px wide @ 1135 */
+ /*        *******           */ 
+ /*      ***********         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*  ***************         */ 
+ /*  ***************         */ 
+  0x77, 0xd2, 0xbd, 0x0e, 0x62, 0x72, 0x9f, 0xd2, 
+  0x01, 0x41, 
+
+ /* Char 114 is 10px wide @ 1145 */
+ /*      **********          */ 
+ /*      ***********         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*               **         */ 
+ /*                *         */ 
+  0x01, 0x1a, 0xd1, 0xbd, 0x9e, 0x42, 0xda, 0x18, 
+
+
+ /* Char 115 is 13px wide @ 1153 */
+ /*       **   ****          */ 
+ /*      **   ******         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      ******   **         */ 
+ /*       ****   **          */ 
+  0x01, 0x22, 0x34, 0xd1, 0x23, 0x6d, 0x0e, 0x52, 
+  0x31, 0x32, 0xd0, 0x63, 0x2d, 0x14, 0x32, 0x01, 
+  0x51, 
+
+ /* Char 116 is 8px wide @ 1170 */
+ /*       **************     */ 
+ /*      **************      */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+  0x01, 0x2d, 0x19, 0xd1, 0xae, 0x22, 0x72, 0x01, 
+  0x41, 
+
+ /* Char 117 is 13px wide @ 1179 */
+ /*       **********         */ 
+ /*      ***********         */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*       **********         */ 
+  0x01, 0x2a, 0xd0, 0xbd, 0x0e, 0x62, 0xda, 0xa0, 
+  0x14, 
+
+ /* Char 118 is 15px wide @ 1188 */
+ /*               **         */ 
+ /*             ****         */ 
+ /*           ****           */ 
+ /*         ****             */ 
+ /*        ***               */ 
+ /*      ***                 */ 
+ /*      **                  */ 
+ /*      ****                */ 
+ /*        ****              */ 
+ /*          ***             */ 
+ /*            ***           */ 
+ /*             ****         */ 
+ /*               **         */ 
+  0x01, 0xa2, 0xd7, 0x4d, 0x54, 0xd5, 0x4d, 0x63, 
+  0xd6, 0x3d, 0x82, 0xd9, 0x4d, 0x94, 0xd9, 0x3d, 
+  0xa3, 0xd9, 0x4d, 0x92, 0x01, 0x41, 
+
+ /* Char 119 is 20px wide @ 1210 */
+ /*               **         */ 
+ /*            *****         */ 
+ /*          ****            */ 
+ /*       *****              */ 
+ /*      ****                */ 
+ /*      *****               */ 
+ /*         ****             */ 
+ /*           ****           */ 
+ /*             ****         */ 
+ /*              ***         */ 
+ /*            *****         */ 
+ /*          *****           */ 
+ /*        ****              */ 
+ /*      ****                */ 
+ /*      ****                */ 
+ /*        *****             */ 
+ /*           ****           */ 
+ /*             ****         */ 
+ /*                *         */ 
+  0x01, 0xa2, 0xd6, 0x5d, 0x44, 0xd4, 0x5d, 0x54, 
+  0xd7, 0x5d, 0x94, 0xd9, 0x4d, 0x94, 0xd8, 0x3d, 
+  0x65, 0xd4, 0x5d, 0x44, 0xd5, 0xf4, 0xd9, 0x5d, 
+  0x94, 0xd9, 0x4d, 0xa1, 0x81, 
+
+ /* Char 120 is 13px wide @ 1239 */
+ /*      *         *         */ 
+ /*      **       **         */ 
+ /*       **     **          */ 
+ /*        ***  **           */ 
+ /*         *****            */ 
+ /*          ***             */ 
+ /*         *****            */ 
+ /*        ***  **           */ 
+ /*       **     **          */ 
+ /*      **       **         */ 
+ /*      *         *         */ 
+  0x01, 0x11, 0x91, 0xd0, 0x27, 0x2d, 0x12, 0x52, 
+  0xd3, 0x32, 0x2d, 0x55, 0xd7, 0x3d, 0x75, 0xd5, 
+  0x32, 0x2d, 0x32, 0x52, 0xd1, 0x27, 0x2d, 0x01, 
+  0x91, 0x01, 0x41, 
+
+ /* Char 121 is 13px wide @ 1266 */
+ /*       **********         */ 
+ /*      **                  */ 
+ /*  *   **                  */ 
+ /*  *   **                  */ 
+ /*  *   **                  */ 
+ /*  *   **                  */ 
+ /*  *   **                  */ 
+ /*  *   **                  */ 
+ /*  *   **                  */ 
+ /*  ***************         */ 
+ /*   **************         */ 
+  0x01, 0x2a, 0xd0, 0x2d, 0x5e, 0x51, 0x32, 0xd5, 
+  0xd2, 0xad, 0x10, 0x14, 
+
+ /* Char 122 is 13px wide @ 1278 */
+ /*      ***      **         */ 
+ /*      ***      **         */ 
+ /*      ****     **         */ 
+ /*      ** **    **         */ 
+ /*      **  **   **         */ 
+ /*      **  **   **         */ 
+ /*      **   **  **         */ 
+ /*      **    ** **         */ 
+ /*      **     ****         */ 
+ /*      **     ****         */ 
+ /*      **      ***         */ 
+  0x01, 0x1f, 0x36, 0x2d, 0x04, 0x52, 0xd0, 0x21, 
+  0x24, 0x2d, 0x0f, 0x22, 0x23, 0x2d, 0x02, 0x32, 
+  0x22, 0xd0, 0x24, 0x21, 0x2d, 0x0f, 0x25, 0x4d, 
+  0x02, 0x63, 0x01, 0x41, 
+
+ /* Char 123 is 6px wide @ 1306 */
+ /*            **            */ 
+ /*        **********        */ 
+ /*      ******  *****       */ 
+ /*      **          **      */ 
+  0xb2, 0xd5, 0xac, 0x62, 0x5b, 0x2a, 0x20, 0x29, 
+
+
+ /* Char 124 is 4px wide @ 1314 */
+ /*    ******************    */ 
+ /*    ******************    */ 
+  0xde, 0xfd, 0x5d, 0xe1, 
+
+ /* Char 125 is 6px wide @ 1318 */
+ /*      **          **      */ 
+ /*      ******  *****       */ 
+ /*       ***********        */ 
+ /*            **            */ 
+  0x01, 0x12, 0xa2, 0xa6, 0x25, 0xcb, 0xd5, 0x20, 
+  0x17, 
+
+ /* Char 126 is 8px wide @ 1327 */
+ /*            *             */ 
+ /*            *             */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+ /*           *              */ 
+  0x01, 0x7f, 0x1d, 0x9e, 0x21, 0x01, 0x91, 
+
+ /* Char 196 is 16px wide @ 1334 */
+ /*      *************       */ 
+ /*      *************       */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **  **  */ 
+ /*           **     **  **  */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **  **  */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*           **     **      */ 
+ /*      *************       */ 
+ /*      ************        */ 
+  0x01, 0x1f, 0xd0, 0xd3, 0xf2, 0x52, 0xd2, 0xf2, 
+  0x52, 0x22, 0xbf, 0x25, 0x2d, 0x22, 0x52, 0x22, 
+  0xbe, 0x12, 0x52, 0xad, 0x0b, 0xc0, 0x13, 
+
+ /* Char 214 is 16px wide @ 1357 */
+ /*       ************       */ 
+ /*      *************       */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **  **  */ 
+ /*      **          **  **  */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **  **  */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      *************       */ 
+ /*        **********        */ 
+  0x01, 0x2c, 0xbd, 0x0b, 0xf2, 0xa2, 0xaf, 0x2a, 
+  0x22, 0x26, 0xf2, 0xa2, 0xa2, 0xa2, 0x22, 0x6e, 
+  0x12, 0xa2, 0xad, 0x0d, 0x0a, 0x01, 0x31, 
+
+ /* Char 220 is 16px wide @ 1380 */
+ /*       *************      */ 
+ /*      *************       */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **              **  */ 
+ /*      **              **  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **              **  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*      **************      */ 
+ /*        ************      */ 
+  0x01, 0x2d, 0x0a, 0xd0, 0xbf, 0x2d, 0x9f, 0x2d, 
+  0x12, 0x6f, 0x2d, 0x92, 0xd1, 0x26, 0xe1, 0x2d, 
+  0x9d, 0x1c, 0xc0, 0x11, 
+
+ /* Char 223 is 16px wide @ 1400 */
+ /*      *************       */ 
+ /*      **************      */ 
+ /*                  **      */ 
+ /*                  **      */ 
+ /*      *           **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **    **    **      */ 
+ /*      **************      */ 
+ /*       ************       */ 
+  0x01, 0x1d, 0x0b, 0xd1, 0xd9, 0xf2, 0xa1, 0xb2, 
+  0xae, 0x52, 0x42, 0x42, 0xad, 0x1b, 0xc0, 0x12, 
+
+
+ /* Char 228 is 14px wide @ 1416 */
+ /*       *****   **         */ 
+ /*      ******   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **    *    */ 
+ /*      **   *   **    *    */ 
+ /*      **   *   **         */ 
+ /*      **   *   **         */ 
+ /*      **   *   **   **    */ 
+ /*      **   *   **         */ 
+ /*      **  ***  **         */ 
+ /*      **********          */ 
+  0x01, 0x25, 0x32, 0xd0, 0x63, 0x2d, 0x02, 0x31, 
+  0x32, 0xd0, 0xf2, 0x31, 0x32, 0x41, 0x8f, 0x23, 
+  0x13, 0x2d, 0x02, 0x31, 0x32, 0x32, 0x82, 0x31, 
+  0x32, 0xd0, 0x22, 0x32, 0x2d, 0x0a, 0x02, 0xd1, 
+
+
+ /* Char 246 is 13px wide @ 1448 */
+ /*       *********          */ 
+ /*      ***********         */ 
+ /*      **       **         */ 
+ /*      **       **   **    */ 
+ /*      **       **    *    */ 
+ /*      **       **         */ 
+ /*      **       **    *    */ 
+ /*      **       **    *    */ 
+ /*      **       **         */ 
+ /*      **       **         */ 
+ /*       *********          */ 
+  0x01, 0x29, 0xd1, 0xbd, 0x02, 0x72, 0xd0, 0x27, 
+  0x23, 0x28, 0x27, 0x24, 0x18, 0x27, 0x2d, 0x0f, 
+  0x27, 0x24, 0x18, 0xf2, 0x72, 0xd1, 0x90, 0x15, 
+
+
+ /* Char 252 is 13px wide @ 1472 */
+ /*       **********         */ 
+ /*      ***********         */ 
+ /*      **                  */ 
+ /*      **            **    */ 
+ /*      **             *    */ 
+ /*      **                  */ 
+ /*      **             *    */ 
+ /*      **            **    */ 
+ /*      **                  */ 
+ /*      **                  */ 
+ /*       **********         */ 
+  0x01, 0x2a, 0xd0, 0xbd, 0x02, 0xd9, 0x2c, 0x28, 
+  0x2d, 0x01, 0x82, 0xd9, 0x2d, 0x01, 0x82, 0xc2, 
+  0x8f, 0x2d, 0xaa, 0x01, 0x41, 
+
+ /* Char 8364 is 15px wide @ 1493 */
+ /*          **  **          */ 
+ /*          **  **          */ 
+ /*       ************       */ 
+ /*      **  **  **  **      */ 
+ /*      **  **  **  **      */ 
+ /*      **  **  **  **      */ 
+ /*      **  **  **  **      */ 
+ /*      **  **  **  **      */ 
+ /*      **  **  **  **      */ 
+ /*      **  **  **  **      */ 
+ /*      **  **  **  **      */ 
+ /*      **          **      */ 
+ /*      **          **      */ 
+ /*      *                   */ 
+  0x01, 0x5f, 0x22, 0x2d, 0x2c, 0xbe, 0x62, 0x22, 
+  0x22, 0x22, 0xaf, 0x2a, 0x2a, 0x1d, 0x51, 
+
+};
+
+/* Character descriptors */
+const FONT_CHAR_INFO Orbitron14ptLengths[] = {
+ { 2}, /*   */
+ { 7}, /* ! */
+ { 8}, /* " */
+ {36}, /* # */
+ {17}, /* $ */
+ {42}, /* % */
+ {42}, /* & */
+ { 4}, /* ' */
+ { 7}, /* ( */
+ { 7}, /* ) */
+ {15}, /* * */
+ { 8}, /* + */
+ { 5}, /* , */
+ { 5}, /* - */
+ { 5}, /* . */
+ {15}, /* / */
+ {36}, /* 0 */
+ { 9}, /* 1 */
+ {18}, /* 2 */
+ {15}, /* 3 */
+ {26}, /* 4 */
+ {15}, /* 5 */
+ {15}, /* 6 */
+ { 7}, /* 7 */
+ {12}, /* 8 */
+ {12}, /* 9 */
+ { 7}, /* : */
+ { 6}, /* ; */
+ {18}, /* < */
+ { 6}, /* = */
+ {20}, /* > */
+ {16}, /* ? */
+ {26}, /* @ */
+ {11}, /* A */
+ {11}, /* B */
+ {10}, /* C */
+ {10}, /* D */
+ {13}, /* E */
+ {11}, /* F */
+ {17}, /* G */
+ {12}, /* H */
+ { 6}, /* I */
+ {10}, /* J */
+ {22}, /* K */
+ { 8}, /* L */
+ {25}, /* M */
+ {22}, /* N */
+ {11}, /* O */
+ {10}, /* P */
+ {13}, /* Q */
+ {22}, /* R */
+ {15}, /* S */
+ {10}, /* T */
+ {11}, /* U */
+ {28}, /* V */
+ {33}, /* W */
+ {30}, /* X */
+ {22}, /* Y */
+ {37}, /* Z */
+ { 7}, /* [ */
+ {16}, /* \ */
+ { 7}, /* ] */
+ { 1}, /* ^ */
+ { 4}, /* _ */
+ { 5}, /* ` */
+ {17}, /* a */
+ {10}, /* b */
+ { 9}, /* c */
+ {11}, /* d */
+ {16}, /* e */
+ { 8}, /* f */
+ {13}, /* g */
+ {10}, /* h */
+ { 7}, /* i */
+ { 6}, /* j */
+ {21}, /* k */
+ { 7}, /* l */
+ {14}, /* m */
+ { 8}, /* n */
+ {10}, /* o */
+ { 9}, /* p */
+ {10}, /* q */
+ { 8}, /* r */
+ {17}, /* s */
+ { 9}, /* t */
+ { 9}, /* u */
+ {22}, /* v */
+ {29}, /* w */
+ {27}, /* x */
+ {12}, /* y */
+ {28}, /* z */
+ { 8}, /* { */
+ { 4}, /* | */
+ { 9}, /* } */
+ { 7}, /* ~ */
+ {23}, /* Ä */
+ {23}, /* Ö */
+ {20}, /* Ü */
+ {16}, /* ß */
+ {32}, /* ä */
+ {24}, /* ö */
+ {21}, /* ü */
+ {15}, /* € */
+};
+
+const uint16_t Orbitron14ptExtra[] = {
+196,214,220,223,228,246,252,8364,65535
+};
+
+/* Font info */
+const struct FONT_DEF Font_Orbitron14pt = {
+         1,   /* width (1 == comressed) */
+        24,   /* character height */
+        32,   /* first char */
+       126,   /* last char */
+    Orbitron14ptBitmaps, Orbitron14ptLengths, Orbitron14ptExtra
+};
+
+/* Font metadata: 
+ * Name:          Orbitron Regular 14pt
+ * Height:        24 px (3 bytes)
+ * Maximum width: 22 px
+ * Storage size:  1611 bytes (compressed by 58%)
+ */
diff --git a/lcd/fonts/orbitron14.h b/lcd/fonts/orbitron14.h
new file mode 100644 (file)
index 0000000..f4a12a3
--- /dev/null
@@ -0,0 +1,3 @@
+#include "lcd/fonts.h"
+
+extern const struct FONT_DEF Font_Orbitron14pt;
diff --git a/lcd/fonts/smallfonts.c b/lcd/fonts/smallfonts.c
new file mode 100644 (file)
index 0000000..9d07c12
--- /dev/null
@@ -0,0 +1,556 @@
+/* Partially based on original code for the KS0108 by Stephane Rey */
+
+/**************************************************************************/
+/*! 
+    @file     smallfonts.c
+    @author   K. Townsend (microBuilder.eu)
+    @date     22 March 2010
+    @version  0.10
+
+    @section LICENSE
+
+    Software License Agreement (BSD License)
+
+    Copyright (c) 2010, microBuilder SARL
+    All rights reserved.
+
+    Redistribution and use in source and binary forms, with or without
+    modification, are permitted provided that the following conditions are met:
+    1. Redistributions of source code must retain the above copyright
+    notice, this list of conditions and the following disclaimer.
+    2. Redistributions in binary form must reproduce the above copyright
+    notice, this list of conditions and the following disclaimer in the
+    documentation and/or other materials provided with the distribution.
+    3. Neither the name of the copyright holders nor the
+    names of its contributors may be used to endorse or promote products
+    derived from this software without specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
+    EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+    WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+    DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
+    DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+    (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+    LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+    ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+    (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+    SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+/**************************************************************************/
+#include "smallfonts.h"
+
+/* System 3x6 - UPPER CASE ONLY */
+const uint8_t au8Font3x6[]= {
+    0x00,0x00,0x00, /* Space */
+    0x00,0x5C,0x00, /* ! */
+    0x0C,0x00,0x0C, /* " */
+    0x7C,0x28,0x7C, /* # */
+    0x7C,0x44,0x7C, /* $ */
+    0x24,0x10,0x48, /* % */
+    0x28,0x54,0x08, /* & */
+    0x00,0x0C,0x00, /* ' */
+    0x38,0x44,0x00, /* ( */
+    0x44,0x38,0x00, /* ) */
+    0x20,0x10,0x08, /* / */
+    0x10,0x38,0x10, /* + */
+    0x80,0x40,0x00, /* , */
+    0x10,0x10,0x10, /* - */
+    0x00,0x40,0x00, /* . */
+    0x20,0x10,0x08, /* / */
+    0x38,0x44,0x38, /* 0 */
+    0x00,0x7C,0x00, /* 1 */
+    0x64,0x54,0x48, /* 2 */
+    0x44,0x54,0x28, /* 3 */
+    0x1C,0x10,0x7C, /* 4 */
+    0x4C,0x54,0x24, /* 5 */
+    0x38,0x54,0x20, /* 6 */
+    0x04,0x74,0x0C, /* 7 */
+    0x28,0x54,0x28, /* 8 */
+    0x08,0x54,0x38, /* 9 */
+    0x00,0x50,0x00, /* : */
+    0x80,0x50,0x00, /* ; */
+    0x10,0x28,0x44, /* < */
+    0x28,0x28,0x28, /* = */
+    0x44,0x28,0x10, /* > */
+    0x04,0x54,0x08, /* ? */
+    0x38,0x4C,0x5C, /* @ */
+    0x78,0x14,0x78, /* A */
+    0x7C,0x54,0x28, /* B */
+    0x38,0x44,0x44, /* C */
+    0x7C,0x44,0x38, /* D */
+    0x7C,0x54,0x44, /* E */
+    0x7C,0x14,0x04, /* F */
+    0x38,0x44,0x34, /* G */
+    0x7C,0x10,0x7C, /* H */
+    0x00,0x7C,0x00, /* I */
+    0x20,0x40,0x3C, /* J */
+    0x7C,0x10,0x6C, /* K */
+    0x7C,0x40,0x40, /* L */
+    0x7C,0x08,0x7C, /* M */
+    0x7C,0x04,0x7C, /* N */
+    0x7C,0x44,0x7C, /* O */
+    0x7C,0x14,0x08, /* P */
+    0x38,0x44,0x78, /* Q */
+    0x7C,0x14,0x68, /* R */
+    0x48,0x54,0x24, /* S */
+    0x04,0x7C,0x04, /* T */
+    0x7C,0x40,0x7C, /* U */
+    0x3C,0x40,0x3C, /* V */
+    0x7C,0x20,0x7C, /* W */
+    0x6C,0x10,0x6C, /* X */
+    0x1C,0x60,0x1C, /* Y */
+    0x64,0x54,0x4C, /* Z */
+    0x7C,0x44,0x00, /* [ */
+    0x08,0x10,0x20, /* \ */
+    0x44,0x7C,0x00, /* ] */
+    0x08,0x04,0x08, /* ^ */
+    0x80,0x80,0x80, /* _ */
+    0x04,0x08,0x00  /* ` */
+};
+
+/* System 5x8 */
+const uint8_t au8Font5x8[]= 
+{
+    0x00,0x00,0x00,0x00,0x00, /* Space */
+    0x00,0x00,0x4f,0x00,0x00, /* ! */
+    0x00,0x07,0x00,0x07,0x00, /* " */
+    0x14,0x7f,0x14,0x7f,0x14, /* # */
+    0x24,0x2a,0x7f,0x2a,0x12, /* $ */
+    0x23,0x13,0x08,0x64,0x62, /* % */
+    0x36,0x49,0x55,0x22,0x20, /* & */
+    0x00,0x05,0x03,0x00,0x00, /* ' */
+    0x00,0x1c,0x22,0x41,0x00, /* ( */
+    0x00,0x41,0x22,0x1c,0x00, /* ) */
+    0x14,0x08,0x3e,0x08,0x14, /* / */
+    0x08,0x08,0x3e,0x08,0x08, /* + */
+    0x50,0x30,0x00,0x00,0x00, /* , */
+    0x08,0x08,0x08,0x08,0x08, /* - */ 
+    0x00,0x60,0x60,0x00,0x00, /* . */
+    0x20,0x10,0x08,0x04,0x02, /* / */
+    0x3e,0x51,0x49,0x45,0x3e, /* 0 */
+    0x00,0x42,0x7f,0x40,0x00, /* 1 */
+    0x42,0x61,0x51,0x49,0x46, /* 2 */
+    0x21,0x41,0x45,0x4b,0x31, /* 3 */
+    0x18,0x14,0x12,0x7f,0x10, /* 4 */
+    0x27,0x45,0x45,0x45,0x39, /* 5 */
+    0x3c,0x4a,0x49,0x49,0x30, /* 6 */
+    0x01,0x71,0x09,0x05,0x03, /* 7 */
+    0x36,0x49,0x49,0x49,0x36, /* 8 */
+    0x06,0x49,0x49,0x29,0x1e, /* 9 */
+    0x00,0x36,0x36,0x00,0x00, /* : */
+    0x00,0x56,0x36,0x00,0x00, /* ; */
+    0x08,0x14,0x22,0x41,0x00, /* < */
+    0x14,0x14,0x14,0x14,0x14, /* = */
+    0x00,0x41,0x22,0x14,0x08, /* > */
+    0x02,0x01,0x51,0x09,0x06, /* ? */
+    0x3e,0x41,0x5d,0x55,0x1e, /* @ */
+    0x7e,0x11,0x11,0x11,0x7e, /* A */
+    0x7f,0x49,0x49,0x49,0x36, /* B */
+    0x3e,0x41,0x41,0x41,0x22, /* C */
+    0x7f,0x41,0x41,0x22,0x1c, /* D */
+    0x7f,0x49,0x49,0x49,0x41, /* E */
+    0x7f,0x09,0x09,0x09,0x01, /* F */
+    0x3e,0x41,0x49,0x49,0x7a, /* G */
+    0x7f,0x08,0x08,0x08,0x7f, /* H */
+    0x00,0x41,0x7f,0x41,0x00, /* I */
+    0x20,0x40,0x41,0x3f,0x01, /* J */
+    0x7f,0x08,0x14,0x22,0x41, /* K */
+    0x7f,0x40,0x40,0x40,0x40, /* L */
+    0x7f,0x02,0x0c,0x02,0x7f, /* M */
+    0x7f,0x04,0x08,0x10,0x7f, /* N */
+    0x3e,0x41,0x41,0x41,0x3e, /* O */
+    0x7f,0x09,0x09,0x09,0x06, /* P */
+    0x3e,0x41,0x51,0x21,0x5e, /* Q */
+    0x7f,0x09,0x19,0x29,0x46, /* R */
+    0x26,0x49,0x49,0x49,0x32, /* S */
+    0x01,0x01,0x7f,0x01,0x01, /* T */
+    0x3f,0x40,0x40,0x40,0x3f, /* U */
+    0x1f,0x20,0x40,0x20,0x1f, /* V */
+    0x3f,0x40,0x38,0x40,0x3f, /* W */
+    0x63,0x14,0x08,0x14,0x63, /* X */
+    0x07,0x08,0x70,0x08,0x07, /* Y */
+    0x61,0x51,0x49,0x45,0x43, /* Z */
+    0x00,0x7f,0x41,0x41,0x00, /* [ */
+    0x02,0x04,0x08,0x10,0x20, /* \ */ 
+    0x00,0x41,0x41,0x7f,0x00, /* ] */
+    0x04,0x02,0x01,0x02,0x04, /* ^ */
+    0x40,0x40,0x40,0x40,0x40, /* _ */
+    0x00,0x00,0x03,0x05,0x00, /* ` */
+    0x20,0x54,0x54,0x54,0x78, /* a */
+    0x7F,0x44,0x44,0x44,0x38, /* b */
+    0x38,0x44,0x44,0x44,0x44, /* c */
+    0x38,0x44,0x44,0x44,0x7f, /* d */
+    0x38,0x54,0x54,0x54,0x18, /* e */
+    0x04,0x04,0x7e,0x05,0x05, /* f */
+    0x08,0x54,0x54,0x54,0x3c, /* g */
+    0x7f,0x08,0x04,0x04,0x78, /* h */
+    0x00,0x44,0x7d,0x40,0x00, /* i */
+    0x20,0x40,0x44,0x3d,0x00, /* j */
+    0x7f,0x10,0x28,0x44,0x00, /* k */
+    0x00,0x41,0x7f,0x40,0x00, /* l */
+    0x7c,0x04,0x7c,0x04,0x78, /* m */
+    0x7c,0x08,0x04,0x04,0x78, /* n */
+    0x38,0x44,0x44,0x44,0x38, /* o */
+    0x7c,0x14,0x14,0x14,0x08, /* p */
+    0x08,0x14,0x14,0x14,0x7c, /* q */
+    0x7c,0x08,0x04,0x04,0x00, /* r */
+    0x48,0x54,0x54,0x54,0x24, /* s */
+    0x04,0x04,0x3f,0x44,0x44, /* t */
+    0x3c,0x40,0x40,0x20,0x7c, /* u */
+    0x1c,0x20,0x40,0x20,0x1c, /* v */
+    0x3c,0x40,0x30,0x40,0x3c, /* w */
+    0x44,0x28,0x10,0x28,0x44, /* x */
+    0x0c,0x50,0x50,0x50,0x3c, /* y */
+    0x44,0x64,0x54,0x4c,0x44, /* z */
+    0x08,0x36,0x41,0x41,0x00, /* { */
+    0x00,0x00,0x77,0x00,0x00, /* | */
+    0x00,0x41,0x41,0x36,0x08, /* } */
+    0x08,0x08,0x2a,0x1c,0x08, /* <- */
+    0x08,0x1c,0x2a,0x08,0x08, /* -> */
+    0xff,0xff,0xff,0xff,0xff, /* ^? */
+};
+
+/* System 7x8 */
+const uint8_t au8Font7x8[]= 
+{
+     0,   0,   0,   0,   0,   0,   0, //' '
+     0,   6,  95,  95,   6,   0,   0, //'!'
+     0,   7,   7,   0,   7,   7,   0, //'"'
+    20, 127, 127,  20, 127, 127,  20, //'#'
+    36,  46, 107, 107,  58,  18,   0, //'$'
+    70, 102,  48,  24,  12, 102,  98, //'%'
+    48, 122,  79,  93,  55, 122,  72, //'&'
+     4,   7,   3,   0,   0,   0,   0, //'''
+     0,  28,  62,  99,  65,   0,   0, //'('
+     0,  65,  99,  62,  28,   0,   0, //')'
+     8,  42,  62,  28,  28,  62,  42, //'*'
+     8,   8,  62,  62,   8,   8,   0, //'+'
+     0, 128, 224,  96,   0,   0,   0, //','
+     8,   8,   8,   8,   8,   8,   0, //'-'
+     0,   0,  96,  96,   0,   0,   0, //'.'
+    96,  48,  24,  12,   6,   3,   1, //'/'
+    62, 127, 113,  89,  77, 127,  62, //'0'
+    64,  66, 127, 127,  64,  64,   0, //'1'
+    98, 115,  89,  73, 111, 102,   0, //'2'
+    34,  99,  73,  73, 127,  54,   0, //'3'
+    24,  28,  22,  83, 127, 127,  80, //'4'
+    39, 103,  69,  69, 125,  57,   0, //'5'
+    60, 126,  75,  73, 121,  48,   0, //'6'
+     3,   3, 113, 121,  15,   7,   0, //'7'
+    54, 127,  73,  73, 127,  54,   0, //'8'
+     6,  79,  73, 105,  63,  30,   0, //'9'
+     0,   0, 102, 102,   0,   0,   0, //':'
+     0, 128, 230, 102,   0,   0,   0, //';'
+     8,  28,  54,  99,  65,   0,   0, //'<'
+    36,  36,  36,  36,  36,  36,   0, //'='
+     0,  65,  99,  54,  28,   8,   0, //'>'
+     2,   3,  81,  89,  15,   6,   0, //'?'
+    62, 127,  65,  93,  93,  31,  30, //'@'
+    124,126,  19,  19, 126, 124,   0, //'A'
+    65, 127, 127,  73,  73, 127,  54, //'B'
+    28,  62,  99,  65,  65,  99,  34, //'C'
+    65, 127, 127,  65,  99,  62,  28, //'D'
+    65, 127, 127,  73,  93,  65,  99, //'E'
+    65, 127, 127,  73,  29,   1,   3, //'F'
+    28,  62,  99,  65,  81, 115, 114, //'G'
+    127,127,   8,   8, 127, 127,   0, //'H'
+     0,  65, 127, 127,  65,   0,   0, //'I'
+    48, 112,  64,  65, 127,  63,   1, //'J'
+    65, 127, 127,   8,  28, 119,  99, //'K'
+    65, 127, 127,  65,  64,  96, 112, //'L'
+    127,127,  14,  28,  14, 127, 127, //'M'
+    127,127,   6,  12,  24, 127, 127, //'N'
+    28,  62,  99,  65,  99,  62,  28, //'O'
+    65, 127, 127,  73,   9,  15,   6, //'P'
+    30,  63,  33, 113, 127,  94,   0, //'Q'
+    65, 127, 127,   9,  25, 127, 102, //'R'
+    38, 111,  77,  89, 115,  50,   0, //'S'
+     3,  65, 127, 127,  65,   3,   0, //'T'
+    127,127,  64,  64, 127, 127,   0, //'U'
+    31,  63,  96,  96,  63,  31,   0, //'V'
+    127,127,  48,  24,  48, 127, 127, //'W'
+    67, 103,  60,  24,  60, 103,  67, //'X'
+     7,  79, 120, 120,  79,   7,   0, //'Y'
+    71,  99, 113,  89,  77, 103, 115, //'Z'
+     0, 127, 127,  65,  65,   0,   0, //'['
+     1,   3,   6,  12,  24,  48,  96, //'\'
+     0,  65,  65, 127, 127,   0,   0, //']'
+     8,  12,   6,   3,   6,  12,   8, //'^'
+    128,128, 128, 128, 128, 128, 128, //'_'
+     0,   0,   3,   7,   4,   0,   0, //'`'
+    32, 116,  84,  84,  60, 120,  64, //'a'
+    65, 127,  63,  72,  72, 120,  48, //'b'
+    56, 124,  68,  68, 108,  40,   0, //'c'
+    48, 120,  72,  73,  63, 127,  64, //'d'
+    56, 124,  84,  84,  92,  24,   0, //'e'
+    72, 126, 127,  73,   3,   2,   0, //'f'
+    56, 188, 164, 164, 252, 120,   0, //'g'
+    65, 127, 127,   8,   4, 124, 120, //'h'
+     0,  68, 125, 125,  64,   0,   0, //'i'
+    96, 224, 128, 128, 253, 125,   0, //'j'
+    65, 127, 127,  16,  56, 108,  68, //'k'
+     0,  65, 127, 127,  64,   0,   0, //'l'
+    120,124,  28,  56,  28, 124, 120, //'m'
+    124,124,   4,   4, 124, 120,   0, //'n'
+    56, 124,  68,  68, 124,  56,   0, //'o'
+    0,  252, 252, 164,  36,  60,  24, //'p'
+    24,  60,  36, 164, 248, 252, 132, //'q'
+    68, 124, 120,  76,   4,  28,  24, //'r'
+    72,  92,  84,  84, 116,  36,   0, //'s'
+     0,   4,  62, 127,  68,  36,   0, //'t'
+    60, 124,  64,  64,  60, 124,  64, //'u'
+    28,  60,  96,  96,  60,  28,   0, //'v'
+    60, 124, 112,  56, 112, 124,  60, //'w'
+    68, 108,  56,  16,  56, 108,  68, //'x'
+    60, 188, 160, 160, 252, 124,   0, //'y'
+    76, 100, 116,  92,  76, 100,   0, //'z'
+     8,   8,  62, 119,  65,  65,   0, //'{'
+     0,   0,   0, 119, 119,   0,   0, //'|'
+    65,  65, 119,  62,   8,   8,   0, //'}'
+     2,   3,   1,   3,   2,   3,   1, //'~'
+    255,129, 129, 129, 129, 129, 255, //'^?'
+    14, 159, 145, 177, 251,  74,   0  //'?'
+};
+  
+/* 8x8 Normal */
+const uint8_t au8Font8x8[]= {
+    0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,       // ASCII -  32
+    0x00,0x00,0x00,0x5F,0x5F,0x00,0x00,0x00,       // ASCII -  33
+    0x00,0x00,0x03,0x07,0x00,0x07,0x03,0x00,       // ASCII -  34
+    0x00,0x10,0x74,0x1C,0x77,0x1C,0x17,0x04,       // ASCII -  35
+    0x00,0x24,0x2E,0x2A,0x7F,0x2A,0x3A,0x10,       // ASCII -  36
+    0x00,0x4C,0x6A,0x76,0x1A,0x6A,0x56,0x33,       // ASCII -  37
+    0x00,0x30,0x7A,0x4F,0x5D,0x37,0x7A,0x48,       // ASCII -  38
+    0x00,0x00,0x04,0x07,0x03,0x00,0x00,0x00,       // ASCII -  39
+    0x00,0x00,0x00,0x1C,0x3E,0x63,0x41,0x00,       // ASCII -  40
+    0x00,0x00,0x41,0x63,0x3E,0x1C,0x00,0x00,       // ASCII -  41
+    0x00,0x08,0x2A,0x3E,0x1C,0x3E,0x2A,0x08,       // ASCII -  42
+    0x00,0x08,0x08,0x3E,0x3E,0x08,0x08,0x00,       // ASCII -  43
+    0x00,0x00,0x00,0x60,0x60,0x00,0x00,0x00,       // ASCII -  44
+    0x00,0x08,0x08,0x08,0x08,0x08,0x08,0x00,       // ASCII -  45
+    0x00,0x00,0x00,0x60,0x60,0x00,0x00,0x00,       // ASCII -  46
+    0x00,0x60,0x30,0x18,0x0C,0x06,0x03,0x01,       // ASCII -  47
+    0x00,0x1C,0x3E,0x61,0x43,0x3E,0x1C,0x00,       // ASCII -  48
+    0x00,0x00,0x44,0x7F,0x7F,0x40,0x00,0x00,       // ASCII -  49
+    0x00,0x46,0x67,0x71,0x59,0x4F,0x66,0x00,       // ASCII -  50
+    0x00,0x22,0x63,0x49,0x4D,0x7F,0x32,0x00,       // ASCII -  51
+    0x00,0x18,0x1C,0x52,0x7F,0x7F,0x50,0x00,       // ASCII -  52
+    0x00,0x2F,0x6F,0x45,0x45,0x7D,0x39,0x00,       // ASCII -  53
+    0x00,0x3C,0x7E,0x4B,0x49,0x79,0x30,0x00,       // ASCII -  54
+    0x00,0x07,0x43,0x71,0x7D,0x0F,0x03,0x00,       // ASCII -  55
+    0x00,0x36,0x7F,0x4D,0x59,0x7F,0x36,0x00,       // ASCII -  56
+    0x00,0x06,0x4F,0x49,0x69,0x3F,0x1E,0x00,       // ASCII -  57
+    0x00,0x00,0x00,0x66,0x66,0x00,0x00,0x00,       // ASCII -  58
+    0x00,0x00,0x00,0x66,0x66,0x00,0x00,0x00,       // ASCII -  59
+    0x00,0x00,0x08,0x1C,0x36,0x63,0x41,0x00,       // ASCII -  60
+    0x00,0x14,0x14,0x14,0x14,0x14,0x14,0x00,       // ASCII -  61
+    0x00,0x00,0x41,0x63,0x36,0x1C,0x08,0x00,       // ASCII -  62
+    0x00,0x02,0x07,0x51,0x59,0x0F,0x06,0x00,       // ASCII -  63
+    0x00,0x3E,0x41,0x5D,0x55,0x5D,0x51,0x1E,       // ASCII -  64
+    0x00,0x40,0x70,0x1D,0x17,0x1F,0x78,0x60,       // ASCII -  65
+    0x00,0x41,0x7F,0x7F,0x49,0x4F,0x7E,0x30,       // ASCII -  66
+    0x00,0x1C,0x3E,0x63,0x41,0x41,0x42,0x27,       // ASCII -  67
+    0x00,0x41,0x7F,0x7F,0x41,0x63,0x3E,0x1C,       // ASCII -  68
+    0x00,0x41,0x7F,0x7F,0x49,0x5D,0x41,0x63,       // ASCII -  69
+    0x00,0x41,0x7F,0x7F,0x49,0x1D,0x01,0x03,       // ASCII -  70
+    0x00,0x1C,0x3E,0x63,0x41,0x51,0x72,0x77,       // ASCII -  71
+    0x00,0x7F,0x7F,0x08,0x08,0x7F,0x7F,0x00,       // ASCII -  72
+    0x00,0x00,0x41,0x7F,0x7F,0x41,0x00,0x00,       // ASCII -  73
+    0x00,0x30,0x70,0x41,0x41,0x7F,0x3F,0x01,       // ASCII -  74
+    0x00,0x7F,0x7F,0x08,0x1C,0x77,0x63,0x41,       // ASCII -  75
+    0x00,0x41,0x7F,0x7F,0x41,0x40,0x60,0x70,       // ASCII -  76
+    0x00,0x7F,0x7E,0x0C,0x18,0x0C,0x7E,0x7F,       // ASCII -  77
+    0x00,0x7F,0x7E,0x0C,0x18,0x30,0x7F,0x7F,       // ASCII -  78
+    0x00,0x1C,0x3E,0x63,0x41,0x63,0x3E,0x1C,       // ASCII -  79
+    0x00,0x41,0x7F,0x7F,0x49,0x09,0x0F,0x06,       // ASCII -  80
+    0x00,0x1C,0x3E,0x63,0x51,0x63,0x3E,0x1C,       // ASCII -  81
+    0x00,0x7F,0x7F,0x09,0x19,0x7F,0x66,0x40,       // ASCII -  82
+    0x00,0x66,0x6F,0x4D,0x59,0x7B,0x33,0x00,       // ASCII -  83
+    0x00,0x03,0x41,0x7F,0x7F,0x41,0x03,0x00,       // ASCII -  84
+    0x00,0x3F,0x7F,0x40,0x40,0x40,0x7F,0x3F,       // ASCII -  85
+    0x00,0x03,0x0F,0x3D,0x70,0x1D,0x07,0x01,       // ASCII -  86
+    0x00,0x0F,0x7F,0x30,0x1C,0x30,0x7F,0x0F,       // ASCII -  87
+    0x00,0x63,0x77,0x1C,0x1C,0x77,0x63,0x00,       // ASCII -  88
+    0x01,0x03,0x47,0x7C,0x78,0x47,0x03,0x01,       // ASCII -  89
+    0x00,0x67,0x73,0x59,0x4D,0x67,0x73,0x00,       // ASCII -  90
+    0x00,0x00,0x00,0x7F,0x7F,0x41,0x41,0x00,       // ASCII -  91
+    0x00,0x01,0x03,0x06,0x0C,0x18,0x30,0x60,       // ASCII -  92
+    0x00,0x00,0x41,0x41,0x7F,0x7F,0x00,0x00,       // ASCII -  93
+    0x00,0x00,0x04,0x06,0x03,0x06,0x04,0x00,       // ASCII -  94
+    0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,       // ASCII -  95
+    0x00,0x00,0x01,0x03,0x06,0x04,0x00,0x00,       // ASCII -  96
+    0x00,0x68,0x6C,0x54,0x54,0x3C,0x78,0x40,       // ASCII -  97
+    0x00,0x41,0x7F,0x3F,0x6C,0x44,0x7C,0x38,       // ASCII -  98
+    0x00,0x38,0x7C,0x44,0x44,0x6C,0x2C,0x00,       // ASCII -  99
+    0x00,0x38,0x7C,0x44,0x49,0x3F,0x7F,0x40,       // ASCII - 100
+    0x00,0x38,0x7C,0x54,0x54,0x5C,0x58,0x00,       // ASCII - 101
+    0x00,0x00,0x48,0x7E,0x7F,0x49,0x0B,0x02,       // ASCII - 102
+    0x00,0x48,0x7C,0x34,0x34,0x2C,0x68,0x44,       // ASCII - 103
+    0x00,0x41,0x7F,0x7F,0x08,0x04,0x7C,0x78,       // ASCII - 104
+    0x00,0x00,0x44,0x7D,0x7D,0x40,0x00,0x00,       // ASCII - 105
+    0x00,0x60,0x60,0x04,0x7D,0x7D,0x00,0x00,       // ASCII - 106
+    0x00,0x41,0x7F,0x7F,0x10,0x78,0x6C,0x44,       // ASCII - 107
+    0x00,0x00,0x41,0x7F,0x7F,0x40,0x00,0x00,       // ASCII - 108
+    0x00,0x7C,0x7C,0x0C,0x78,0x0C,0x7C,0x78,       // ASCII - 109
+    0x00,0x44,0x7C,0x7C,0x08,0x04,0x7C,0x78,       // ASCII - 110
+    0x00,0x38,0x7C,0x44,0x44,0x7C,0x38,0x00,       // ASCII - 111
+    0x00,0x04,0x7C,0x78,0x24,0x24,0x3C,0x18,       // ASCII - 112
+    0x00,0x18,0x3C,0x24,0x24,0x78,0x7C,0x00,       // ASCII - 113
+    0x00,0x44,0x7C,0x78,0x4C,0x04,0x1C,0x18,       // ASCII - 114
+    0x00,0x48,0x5C,0x5C,0x74,0x74,0x24,0x00,       // ASCII - 115
+    0x00,0x00,0x04,0x3E,0x7F,0x44,0x24,0x00,       // ASCII - 116
+    0x00,0x3C,0x7C,0x40,0x40,0x3C,0x7C,0x40,       // ASCII - 117
+    0x00,0x04,0x1C,0x3C,0x60,0x30,0x1C,0x04,       // ASCII - 118
+    0x00,0x1C,0x7C,0x30,0x1C,0x30,0x7C,0x1C,       // ASCII - 119
+    0x00,0x44,0x6C,0x3C,0x10,0x78,0x6C,0x44,       // ASCII - 120
+    0x00,0x44,0x4C,0x1C,0x70,0x64,0x1C,0x0C,       // ASCII - 121
+    0x00,0x4C,0x64,0x74,0x5C,0x4C,0x64,0x00,       // ASCII - 122
+    0x00,0x08,0x08,0x3E,0x77,0x41,0x41,0x00,       // ASCII - 123
+    0x00,0x00,0x00,0x7F,0x7F,0x00,0x00,0x00,       // ASCII - 124
+    0x00,0x41,0x41,0x77,0x3E,0x08,0x08,0x00,       // ASCII - 125
+    0x00,0x02,0x01,0x01,0x03,0x02,0x02,0x01,       // ASCII - 126
+    0x00,0x60,0x78,0x4E,0x47,0x5E,0x78,0x60,       // ASCII - 127
+    0x00,0x1C,0x3E,0x23,0x41,0x41,0x42,0x27,       // ASCII - 128
+    0x00,0x3D,0x7D,0x40,0x41,0x3D,0x7C,0x40,       // ASCII - 129
+};
+
+/* 8x8 Thin */
+const uint8_t au8Font8x8Thin[]= {
+    0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
+    0x00,0x00,0x00,0x5F,0x00,0x00,0x00,0x00,
+    0x00,0x00,0x07,0x00,0x00,0x07,0x00,0x00,
+    0x00,0x14,0x7F,0x14,0x14,0x7F,0x14,0x00,
+    0x00,0x24,0x2A,0x6B,0x6B,0x2A,0x12,0x00,
+    0x00,0x46,0x26,0x10,0x08,0x64,0x62,0x00,
+    0x30,0x4A,0x45,0x4D,0x32,0x48,0x48,0x00,
+    0x00,0x00,0x04,0x03,0x00,0x00,0x00,0x00,
+    0x00,0x1C,0x22,0x41,0x00,0x00,0x00,0x00,
+    0x00,0x00,0x41,0x22,0x1C,0x00,0x00,0x00,
+    0x08,0x2A,0x1C,0x1C,0x1C,0x2A,0x08,0x00,
+    0x00,0x08,0x08,0x3E,0x08,0x08,0x00,0x00,
+    0x00,0x00,0x80,0x60,0x00,0x00,0x00,0x00,
+    0x00,0x08,0x08,0x08,0x08,0x08,0x08,0x00,
+    0x00,0x00,0x00,0x60,0x00,0x00,0x00,0x00,
+    0x00,0x40,0x20,0x10,0x08,0x04,0x02,0x00,
+    0x00,0x3E,0x61,0x51,0x49,0x45,0x3E,0x00,
+    0x00,0x44,0x42,0x7F,0x40,0x40,0x00,0x00,
+    0x00,0x62,0x51,0x51,0x49,0x49,0x66,0x00,
+    0x00,0x22,0x41,0x49,0x49,0x49,0x36,0x00,
+    0x10,0x18,0x14,0x52,0x7F,0x50,0x10,0x00,
+    0x00,0x27,0x45,0x45,0x45,0x45,0x39,0x00,
+    0x00,0x3C,0x4A,0x49,0x49,0x49,0x30,0x00,
+    0x00,0x03,0x01,0x71,0x09,0x05,0x03,0x00,
+    0x00,0x36,0x49,0x49,0x49,0x49,0x36,0x00,
+    0x00,0x06,0x49,0x49,0x49,0x29,0x1E,0x00,
+    0x00,0x00,0x00,0x66,0x00,0x00,0x00,0x00,
+    0x00,0x00,0x80,0x66,0x00,0x00,0x00,0x00,
+    0x00,0x08,0x14,0x22,0x41,0x00,0x00,0x00,
+    0x00,0x24,0x24,0x24,0x24,0x24,0x24,0x00,
+    0x00,0x00,0x00,0x41,0x22,0x14,0x08,0x00,
+    0x00,0x02,0x01,0x01,0x51,0x09,0x06,0x00,
+    0x00,0x3E,0x41,0x5D,0x55,0x55,0x1E,0x00,
+    0x00,0x7C,0x12,0x11,0x11,0x12,0x7C,0x00,
+    0x00,0x41,0x7F,0x49,0x49,0x49,0x36,0x00,
+    0x00,0x1C,0x22,0x41,0x41,0x41,0x22,0x00,
+    0x00,0x41,0x7F,0x41,0x41,0x22,0x1C,0x00,
+    0x00,0x41,0x7F,0x49,0x5D,0x41,0x63,0x00,
+    0x00,0x41,0x7F,0x49,0x1D,0x01,0x03,0x00,
+    0x00,0x1C,0x22,0x41,0x51,0x51,0x72,0x00,
+    0x00,0x7F,0x08,0x08,0x08,0x08,0x7F,0x00,
+    0x00,0x00,0x41,0x7F,0x41,0x00,0x00,0x00,
+    0x00,0x30,0x40,0x40,0x41,0x3F,0x01,0x00,
+    0x00,0x41,0x7F,0x08,0x14,0x22,0x41,0x40,
+    0x00,0x41,0x7F,0x41,0x40,0x40,0x60,0x00,
+    0x00,0x7F,0x01,0x02,0x04,0x02,0x01,0x7F,
+    0x00,0x7F,0x01,0x02,0x04,0x08,0x7F,0x00,
+    0x00,0x3E,0x41,0x41,0x41,0x41,0x3E,0x00,
+    0x00,0x41,0x7F,0x49,0x09,0x09,0x06,0x00,
+    0x00,0x1E,0x21,0x21,0x31,0x21,0x5E,0x40,
+    0x00,0x41,0x7F,0x49,0x19,0x29,0x46,0x00,
+    0x00,0x26,0x49,0x49,0x49,0x49,0x32,0x00,
+    0x00,0x03,0x01,0x41,0x7F,0x41,0x01,0x03,
+    0x00,0x3F,0x40,0x40,0x40,0x40,0x3F,0x00,
+    0x00,0x0F,0x10,0x20,0x40,0x20,0x10,0x0F,
+    0x00,0x3F,0x40,0x40,0x38,0x40,0x40,0x3F,
+    0x00,0x41,0x22,0x14,0x08,0x14,0x22,0x41,
+    0x00,0x01,0x02,0x44,0x78,0x44,0x02,0x01,
+    0x00,0x43,0x61,0x51,0x49,0x45,0x43,0x61,
+    0x00,0x7F,0x41,0x41,0x41,0x00,0x00,0x00,
+    0x01,0x02,0x04,0x08,0x10,0x20,0x40,0x00,
+    0x00,0x41,0x41,0x41,0x7F,0x00,0x00,0x00,
+    0x08,0x04,0x02,0x01,0x02,0x04,0x08,0x00,
+    0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
+    0x00,0x00,0x00,0x03,0x04,0x00,0x00,0x00,
+    0x00,0x20,0x54,0x54,0x54,0x54,0x78,0x40,
+    0x00,0x01,0x7F,0x30,0x48,0x48,0x48,0x30,
+    0x00,0x38,0x44,0x44,0x44,0x44,0x28,0x00,
+    0x00,0x30,0x48,0x48,0x48,0x31,0x7F,0x40,
+    0x00,0x38,0x54,0x54,0x54,0x54,0x18,0x00,
+    0x00,0x00,0x48,0x7E,0x49,0x01,0x02,0x00,
+    0x00,0x98,0xA4,0xA4,0xA4,0xA4,0x78,0x04,
+    0x00,0x41,0x7F,0x08,0x04,0x04,0x78,0x00,
+    0x00,0x00,0x44,0x7D,0x40,0x00,0x00,0x00,
+    0x00,0x60,0x80,0x80,0x80,0x84,0x7D,0x00,
+    0x00,0x01,0x7F,0x10,0x28,0x44,0x40,0x00,
+    0x00,0x00,0x41,0x7F,0x40,0x00,0x00,0x00,
+    0x00,0x7C,0x04,0x04,0x78,0x04,0x04,0x78,
+    0x00,0x7C,0x08,0x04,0x04,0x04,0x78,0x00,
+    0x00,0x38,0x44,0x44,0x44,0x44,0x38,0x00,
+    0x00,0x84,0xFC,0x98,0x24,0x24,0x18,0x00,
+    0x00,0x18,0x24,0x24,0x98,0xFC,0x84,0x00,
+    0x00,0x44,0x7C,0x48,0x04,0x04,0x18,0x00,
+    0x00,0x48,0x54,0x54,0x54,0x54,0x24,0x00,
+    0x00,0x04,0x04,0x3F,0x44,0x44,0x20,0x00,
+    0x00,0x3C,0x40,0x40,0x40,0x20,0x7C,0x00,
+    0x00,0x0C,0x10,0x20,0x40,0x20,0x10,0x0C,
+    0x00,0x3C,0x40,0x40,0x38,0x40,0x40,0x3C,
+    0x00,0x44,0x28,0x10,0x28,0x44,0x00,0x00,
+    0x00,0x9C,0xA0,0xA0,0xA0,0xA0,0x7C,0x00,
+    0x00,0x44,0x64,0x54,0x4C,0x44,0x00,0x00,
+    0x00,0x08,0x08,0x36,0x41,0x41,0x00,0x00,
+    0x00,0x00,0x00,0x77,0x00,0x00,0x00,0x00,
+    0x00,0x00,0x41,0x41,0x36,0x08,0x08,0x00,
+    0x00,0x02,0x01,0x01,0x02,0x02,0x01,0x00,
+    0x00,0x70,0x48,0x44,0x42,0x44,0x48,0x70,
+    0x00,0x0E,0x91,0x91,0xB1,0xB1,0x4A,0x00,
+    0x00,0x3A,0x40,0x40,0x40,0x7A,0x40,0x00,
+    0x00,0x38,0x54,0x54,0x55,0x55,0x18,0x00,
+    0x00,0x22,0x55,0x55,0x55,0x79,0x42,0x00,
+    0x00,0x21,0x54,0x54,0x54,0x78,0x41,0x00,
+    0x00,0x20,0x55,0x55,0x54,0x78,0x40,0x00,
+    0x00,0x20,0x54,0x55,0x54,0x78,0x40,0x00,
+    0x00,0x18,0x24,0xA4,0xA4,0xE4,0x40,0x00,
+    0x00,0x3A,0x55,0x55,0x55,0x55,0x1A,0x00,
+    0x00,0x39,0x54,0x54,0x54,0x54,0x19,0x00,
+    0x00,0x38,0x55,0x55,0x54,0x54,0x18,0x00,
+    0x00,0x00,0x01,0x44,0x7C,0x41,0x00,0x00,
+    0x02,0x01,0x45,0x7D,0x41,0x01,0x02,0x00,
+    0x00,0x00,0x01,0x45,0x7C,0x40,0x00,0x00,
+    0x00,0x79,0x14,0x12,0x12,0x14,0x79,0x00,
+    0x00,0x70,0x28,0x2B,0x2B,0x28,0x70,0x00,
+    0x00,0x44,0x7C,0x54,0x55,0x45,0x00,0x00,
+    0x00,0x20,0x54,0x54,0x58,0x38,0x54,0x54,
+    0x00,0x7C,0x0A,0x09,0x09,0x7F,0x49,0x49,
+    0x00,0x30,0x4A,0x49,0x49,0x4A,0x30,0x00,
+    0x00,0x32,0x48,0x48,0x48,0x48,0x32,0x00,
+    0x00,0x30,0x49,0x4A,0x48,0x48,0x30,0x00,
+    0x00,0x38,0x42,0x41,0x41,0x42,0x38,0x00,
+    0x00,0x38,0x41,0x42,0x40,0x40,0x38,0x00,
+    0x00,0x1A,0xA0,0xA0,0xA0,0xA0,0x7A,0x00,
+    0x00,0x19,0x24,0x42,0x42,0x24,0x19,0x00,
+    0x00,0x3D,0x40,0x40,0x40,0x40,0x3D,0x00,
+    0x00,0x18,0x24,0x24,0xE7,0x24,0x24,0x00,
+    0x00,0x68,0x5E,0x49,0x41,0x42,0x20,0x00,
+    0x00,0x15,0x16,0x7C,0x16,0x15,0x00,0x00,
+    0x81,0xFF,0x85,0x05,0x17,0xFA,0x90,0x50,
+    0x40,0x88,0x88,0x7F,0x09,0x09,0x02,0x00,
+    0x00,0x20,0x54,0x54,0x55,0x79,0x40,0x00,
+};
+
+/* Global variables */
+const struct FONT_DEF Font_3x6     = {3, 6, 32,  96, au8Font3x6,    NULL,NULL};
+const struct FONT_DEF Font_5x8     = {5, 8, 32, 128, au8Font5x8,    NULL,NULL};
+const struct FONT_DEF Font_7x8     = {7, 8, 32, 128, au8Font7x8,    NULL,NULL};
+const struct FONT_DEF Font_8x8     = {8, 8, 32, 128, au8Font8x8,    NULL,NULL};
+const struct FONT_DEF Font_8x8Thin = {8, 8, 32, 128, au8Font8x8Thin,NULL,NULL};
+
diff --git a/lcd/fonts/smallfonts.h b/lcd/fonts/smallfonts.h
new file mode 100644 (file)
index 0000000..132243e
--- /dev/null
@@ -0,0 +1,52 @@
+/**************************************************************************/
+/*! 
+    @file     smallfonts.h
+    @author   K. Townsend (microBuilder.eu)
+    @date     22 March 2010
+    @version  0.10
+
+    @section LICENSE
+
+    Software License Agreement (BSD License)
+
+    Copyright (c) 2010, microBuilder SARL
+    All rights reserved.
+
+    Redistribution and use in source and binary forms, with or without
+    modification, are permitted provided that the following conditions are met:
+    1. Redistributions of source code must retain the above copyright
+    notice, this list of conditions and the following disclaimer.
+    2. Redistributions in binary form must reproduce the above copyright
+    notice, this list of conditions and the following disclaimer in the
+    documentation and/or other materials provided with the distribution.
+    3. Neither the name of the copyright holders nor the
+    names of its contributors may be used to endorse or promote products
+    derived from this software without specific prior written permission.
+
+    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
+    EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+    WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+    DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
+    DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+    (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+    LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+    ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+    (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+    SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+/**************************************************************************/
+#ifndef __SMALLFONTS_H_
+#define __SMALLFONTS_H_
+
+#include "lcd/fonts.h"
+
+/* Partially based on original code for the KS0108 by Stephane Rey */
+/* Current version by Kevin Townsend */
+
+extern const struct FONT_DEF Font_3x6;
+extern const struct FONT_DEF Font_5x8;
+extern const struct FONT_DEF Font_7x8;
+extern const struct FONT_DEF Font_8x8;
+extern const struct FONT_DEF Font_8x8Thin;
+
+#endif
diff --git a/lcd/fonts/ubuntu18.c b/lcd/fonts/ubuntu18.c
new file mode 100644 (file)
index 0000000..0554af2
--- /dev/null
@@ -0,0 +1,1722 @@
+#include "ubuntu18.h"
+
+/* Font data for Ubuntu Regular 18pt */
+
+/* Copyright 2010 Canonical Ltd.  Licensed under the Ubuntu Font Licence 1.0
+ * 
+ */
+
+/* This file created by makefont.pl by Sec <sec@42.org> */
+
+/* Bitmaps */
+const uint8_t Ubuntu18ptBitmaps[] = {
+ /* Char 32 is 6px wide @ 0 */
+ /*                            */ 
+  0x09, 0x01, 
+
+ /* Char 33 is 7px wide @ 2 */
+ /*     ***  ************      */ 
+ /*     ***  ************      */ 
+  0x02, 0xcf, 0x32, 0xc0, 0x47, 
+
+ /* Char 34 is 10px wide @ 7 */
+ /*                  ******    */ 
+ /*                  ******    */ 
+ /*                            */ 
+ /*                            */ 
+ /*                  ******    */ 
+ /*                  ******    */ 
+  0x03, 0x9f, 0x60, 0x3c, 0xf6, 0x02, 0xb1, 
+
+ /* Char 35 is 17px wide @ 14 */
+ /*         **     **          */ 
+ /*     *** **     **          */ 
+ /*     *********  **          */ 
+ /*       *************        */ 
+ /*         **  *********      */ 
+ /*         **     ** ***      */ 
+ /*         **     **          */ 
+ /*         **     **          */ 
+ /*     *** **     **          */ 
+ /*     *********  **          */ 
+ /*       *************        */ 
+ /*         **  *********      */ 
+ /*         **     ** ***      */ 
+ /*         **     **          */ 
+  0x01, 0x62, 0x52, 0xd0, 0x31, 0x25, 0x2d, 0x09, 
+  0x22, 0xd2, 0xd0, 0xd2, 0x22, 0x9d, 0x02, 0x52, 
+  0x13, 0xd0, 0xf2, 0x52, 0xd0, 0x31, 0x25, 0x2d, 
+  0x09, 0x22, 0xd2, 0xd0, 0xd2, 0x22, 0x9d, 0x02, 
+  0x52, 0x13, 0xd0, 0x25, 0x20, 0x31, 
+
+ /* Char 36 is 14px wide @ 52 */
+ /*      **       ****         */ 
+ /*     ***      ******        */ 
+ /*     **       **  **        */ 
+ /*     **      **    **       */ 
+ /*     **      **    **       */ 
+ /*  *****     **     *****    */ 
+ /*  *****     **     *****    */ 
+ /*     **    **      **       */ 
+ /*     ***  ***      **       */ 
+ /*      ******       **       */ 
+ /*       ****                 */ 
+  0x01, 0x32, 0x74, 0xc3, 0x66, 0xb2, 0x72, 0x22, 
+  0xbf, 0x26, 0x24, 0x27, 0xf5, 0x52, 0x55, 0x72, 
+  0x42, 0x62, 0xa3, 0x23, 0x62, 0xb6, 0x72, 0xc4, 
+  0x03, 0x81, 
+
+ /* Char 37 is 21px wide @ 78 */
+ /*              ******        */ 
+ /*             ********       */ 
+ /*            ***    ***      */ 
+ /*     *      **      **      */ 
+ /*     **     **      **      */ 
+ /*      ***   ***    ***      */ 
+ /*       ****  ********       */ 
+ /*         ***  ******        */ 
+ /*          ****              */ 
+ /*            ***             */ 
+ /*             ****           */ 
+ /*       ******  ***          */ 
+ /*      ********  ****        */ 
+ /*     ***    ***   ***       */ 
+ /*     **      **     **      */ 
+ /*     **      **      *      */ 
+ /*     ***    ***             */ 
+ /*      ********              */ 
+ /*       ******               */ 
+  0x01, 0xb6, 0xd6, 0x8d, 0x43, 0x43, 0x91, 0x62, 
+  0x62, 0x92, 0x52, 0x62, 0xa3, 0x33, 0x43, 0xb4, 
+  0x28, 0xd1, 0x32, 0x6d, 0x34, 0xdb, 0x3d, 0xb4, 
+  0xd3, 0x62, 0x3d, 0x18, 0x24, 0xb3, 0x43, 0x33, 
+  0xa2, 0x62, 0x52, 0x92, 0x62, 0x61, 0x93, 0x43, 
+  0xd4, 0x8d, 0x66, 0x01, 0xc1, 
+
+ /* Char 38 is 17px wide @ 123 */
+ /*       ****                 */ 
+ /*      *******               */ 
+ /*      **   **   ****        */ 
+ /*     ***    *********       */ 
+ /*     **     ****   ***      */ 
+ /*     **     ***     **      */ 
+ /*     **    *****    **      */ 
+ /*     **   *** ***  ***      */ 
+ /*     *** ***   ******       */ 
+ /*      *****     ****        */ 
+ /*       ***                  */ 
+ /*      *****                 */ 
+ /*     **   ***               */ 
+ /*     **    **               */ 
+  0x01, 0x44, 0xd8, 0x7d, 0x62, 0x32, 0x34, 0xb3, 
+  0x49, 0xa2, 0x54, 0x33, 0x92, 0x53, 0x52, 0x92, 
+  0x45, 0x42, 0x92, 0x33, 0x13, 0x23, 0x93, 0x13, 
+  0x36, 0xb5, 0x54, 0xd0, 0x3d, 0x95, 0xd7, 0x23, 
+  0x3d, 0x52, 0x42, 0x03, 0x61, 
+
+ /* Char 39 is 6px wide @ 160 */
+ /*                  ******    */ 
+ /*                  ******    */ 
+  0x03, 0x9f, 0x60, 0x2b, 
+
+ /* Char 40 is 8px wide @ 164 */
+ /*        *********           */ 
+ /*      *************         */ 
+ /*    *****       *****       */ 
+ /*  ***               ***     */ 
+ /* **                   **    */ 
+  0x02, 0xf9, 0xd2, 0xd0, 0xb5, 0x75, 0x73, 0xd2, 
+  0x34, 0x2d, 0x62, 0x01, 0x11, 
+
+ /* Char 41 is 8px wide @ 177 */
+ /* **                   **    */ 
+ /*  ***               ***     */ 
+ /*    *****       *****       */ 
+ /*      *************         */ 
+ /*        *********           */ 
+  0xdd, 0x2d, 0x62, 0x43, 0xd2, 0x37, 0x57, 0x5b, 
+  0xd0, 0xd2, 0x90, 0x32, 
+
+ /* Char 42 is 12px wide @ 189 */
+ /*                  **        */ 
+ /*              *   **        */ 
+ /*             *** **         */ 
+ /*              ********      */ 
+ /*                ******      */ 
+ /*              ********      */ 
+ /*             *** **         */ 
+ /*              *   **        */ 
+ /*                  **        */ 
+  0x03, 0x92, 0xd7, 0x13, 0x2d, 0x63, 0x12, 0xd8, 
+  0x8d, 0x76, 0xd5, 0x8d, 0x43, 0x12, 0xd8, 0x13, 
+  0x2d, 0xb2, 0x01, 0x51, 
+
+ /* Char 43 is 14px wide @ 209 */
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*      ************          */ 
+ /*      ************          */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+  0x01, 0x8e, 0x32, 0xd6, 0xfc, 0xd6, 0xe3, 0x20, 
+  0x1c, 
+
+ /* Char 44 is 6px wide @ 218 */
+ /* **                         */ 
+ /* *******                    */ 
+ /*    ****                    */ 
+  0xdd, 0x2d, 0xb7, 0xd9, 0x40, 0x3b, 
+
+ /* Char 45 is 8px wide @ 224 */
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+ /*           **               */ 
+  0x01, 0x8e, 0x42, 0x01, 0xc1, 
+
+ /* Char 46 is 6px wide @ 229 */
+ /*     ***                    */ 
+ /*     ***                    */ 
+ /*     ***                    */ 
+  0x01, 0x2e, 0x13, 0x03, 0xb1, 
+
+ /* Char 47 is 10px wide @ 234 */
+ /* ****                       */ 
+ /*  ******                    */ 
+ /*     *****                  */ 
+ /*       ******               */ 
+ /*          *****             */ 
+ /*            ******          */ 
+ /*               *****        */ 
+ /*                 ******     */ 
+ /*                    ****    */ 
+ /*                       *    */ 
+  0xe4, 0xda, 0x6d, 0xa5, 0xda, 0x6d, 0xa5, 0xda, 
+  0x6d, 0xa5, 0xda, 0x6d, 0xa4, 0xdc, 0x13, 
+
+ /* Char 48 is 14px wide @ 249 */
+ /*          *******           */ 
+ /*       *************        */ 
+ /*      ****       ****       */ 
+ /*      **           **       */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*      **           **       */ 
+ /*      ****       ****       */ 
+ /*       *************        */ 
+ /*          *******           */ 
+  0x01, 0x77, 0xd3, 0xd0, 0xc4, 0x74, 0xb2, 0xb2, 
+  0xae, 0x22, 0xd0, 0x2a, 0x2b, 0x2b, 0x47, 0x4c, 
+  0xd0, 0xd3, 0x70, 0x18, 
+
+ /* Char 49 is 14px wide @ 269 */
+ /*                 **         */ 
+ /*                 ***        */ 
+ /*                  **        */ 
+ /*                   **       */ 
+ /*     *****************      */ 
+ /*     *****************      */ 
+  0x05, 0x22, 0xdb, 0x3d, 0xb2, 0xdc, 0x2a, 0xfd, 
+  0x40, 0x7b, 
+
+ /* Char 50 is 14px wide @ 279 */
+ /*     ***           **       */ 
+ /*     ****          **       */ 
+ /*     ** ***        ***      */ 
+ /*     **  ***        **      */ 
+ /*     **   ***       **      */ 
+ /*     **    ***      **      */ 
+ /*     **     ***     **      */ 
+ /*     **      ***   **       */ 
+ /*     **       *******       */ 
+ /*     **         ****        */ 
+ /*     **                     */ 
+  0x02, 0xc3, 0xb2, 0xa4, 0xa2, 0xa2, 0x13, 0x83, 
+  0x92, 0x23, 0x82, 0x92, 0x33, 0x72, 0x92, 0x43, 
+  0x62, 0x92, 0x53, 0x52, 0x92, 0x63, 0x32, 0xa2, 
+  0x77, 0xa2, 0x94, 0xb2, 0x02, 0x21, 
+
+ /* Char 51 is 14px wide @ 309 */
+ /*      **            *       */ 
+ /*     ***           **       */ 
+ /*     **             **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      ***    **      */ 
+ /*     ***    ****   **       */ 
+ /*      ***  **********       */ 
+ /*       ******   ****        */ 
+ /*        ****                */ 
+  0x01, 0x32, 0xc1, 0xa3, 0xb2, 0xa2, 0xd0, 0x29, 
+  0xe1, 0x26, 0x25, 0x29, 0x26, 0x34, 0x29, 0x34, 
+  0x43, 0x2b, 0x32, 0xac, 0x63, 0x4d, 0x14, 0x03, 
+  0x71, 
+
+ /* Char 52 is 14px wide @ 334 */
+ /*         ***                */ 
+ /*         *****              */ 
+ /*         ** ***             */ 
+ /*         **  ****           */ 
+ /*         **    ***          */ 
+ /*         **     ***         */ 
+ /*         **      ***        */ 
+ /*         **       ****      */ 
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*         **                 */ 
+ /*         **                 */ 
+  0x01, 0x63, 0xda, 0x5d, 0x82, 0x13, 0xd7, 0x22, 
+  0x4d, 0x52, 0x43, 0xd4, 0x25, 0x3d, 0x32, 0x63, 
+  0xd2, 0x27, 0x49, 0xfd, 0x4d, 0x0f, 0x20, 0x1e, 
+
+
+ /* Char 53 is 14px wide @ 358 */
+ /*      **                    */ 
+ /*     **       **            */ 
+ /*     **       ********      */ 
+ /*     **       ********      */ 
+ /*     **       **    **      */ 
+ /*     **      ***    **      */ 
+ /*     ***     **     **      */ 
+ /*      ***   ***     **      */ 
+ /*      ********      **      */ 
+ /*        *****               */ 
+  0x02, 0xd2, 0xda, 0x27, 0x2d, 0x2f, 0x27, 0x89, 
+  0x27, 0x24, 0x29, 0x26, 0x34, 0x29, 0x35, 0x25, 
+  0x2a, 0x33, 0x35, 0x2a, 0x86, 0x2c, 0x50, 0x36, 
+
+
+ /* Char 54 is 14px wide @ 382 */
+ /*         *******            */ 
+ /*       ***********          */ 
+ /*      ***    ******         */ 
+ /*     ***      **  **        */ 
+ /*     **       **  ***       */ 
+ /*     **       **   **       */ 
+ /*     **       **   ***      */ 
+ /*     ***     ***    **      */ 
+ /*      ***   ***     **      */ 
+ /*       ********     **      */ 
+ /*        *****               */ 
+  0x03, 0x07, 0xd4, 0xbd, 0x13, 0x46, 0xc3, 0x62, 
+  0x22, 0xb2, 0x72, 0x23, 0xa2, 0x72, 0x32, 0xa2, 
+  0x72, 0x33, 0x93, 0x53, 0x42, 0xa3, 0x33, 0x52, 
+  0xb8, 0x52, 0xc5, 0x01, 0xc1, 
+
+ /* Char 55 is 14px wide @ 411 */
+ /*                    **      */ 
+ /*                    **      */ 
+ /*                    **      */ 
+ /*     ***            **      */ 
+ /*     *******        **      */ 
+ /*        ******      **      */ 
+ /*           *****    **      */ 
+ /*              ****  **      */ 
+ /*                *** **      */ 
+ /*                  ****      */ 
+ /*                   ***      */ 
+  0x02, 0x1e, 0x12, 0x93, 0xc2, 0x97, 0x82, 0xc6, 
+  0x62, 0xd2, 0x54, 0x2d, 0x54, 0x22, 0xd7, 0x31, 
+  0x2d, 0x94, 0xda, 0x30, 0x2d, 
+
+ /* Char 56 is 14px wide @ 432 */
+ /*        ***     ***         */ 
+ /*      ******   *****        */ 
+ /*      **   ** ***  **       */ 
+ /*     ***    ****   ***      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **     ***     **      */ 
+ /*     **     ***     **      */ 
+ /*     ***   ****    ***      */ 
+ /*      **  *** ***  **       */ 
+ /*      ******   ******       */ 
+ /*        ***     ***         */ 
+  0x01, 0x53, 0x53, 0xd0, 0x63, 0x5c, 0x23, 0x21, 
+  0x32, 0x2a, 0x34, 0x43, 0x39, 0xf2, 0x62, 0x52, 
+  0x9f, 0x25, 0x35, 0x29, 0x33, 0x44, 0x3a, 0x22, 
+  0x31, 0x32, 0x2b, 0x63, 0x6d, 0x03, 0x53, 0x01, 
+  0x61, 
+
+ /* Char 57 is 14px wide @ 465 */
+ /*               ****         */ 
+ /*     **      *******        */ 
+ /*     **      ***  ***       */ 
+ /*     **     ***    ***      */ 
+ /*     ***    **      **      */ 
+ /*      **    **      **      */ 
+ /*      ***   **      **      */ 
+ /*       ***  **     ***      */ 
+ /*        *******   ***       */ 
+ /*         ***********        */ 
+ /*           *******          */ 
+  0x01, 0xc4, 0xc2, 0x67, 0xb2, 0x63, 0x23, 0xa2, 
+  0x53, 0x43, 0x93, 0x42, 0x62, 0xa2, 0x42, 0x62, 
+  0xa3, 0x32, 0x62, 0xb3, 0x22, 0x53, 0xc7, 0x33, 
+  0xd1, 0xbd, 0x47, 0x03, 0x11, 
+
+ /* Char 58 is 6px wide @ 494 */
+ /*     ***       ***          */ 
+ /*     ***       ***          */ 
+ /*     ***       ***          */ 
+  0x01, 0x2e, 0x13, 0x73, 0x03, 0x11, 
+
+ /* Char 59 is 6px wide @ 500 */
+ /* **            ***          */ 
+ /* *******       ***          */ 
+ /*    ****       ***          */ 
+  0xdd, 0x2c, 0x39, 0x77, 0x3c, 0x47, 0x30, 0x31, 
+
+
+ /* Char 60 is 14px wide @ 508 */
+ /*            *               */ 
+ /*           ***              */ 
+ /*           ***              */ 
+ /*          *****             */ 
+ /*          ** **             */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*        ***   ***           */ 
+ /*        **     **           */ 
+ /*        **     **           */ 
+ /*       **       **          */ 
+ /*        *       *           */ 
+  0x01, 0x91, 0xdb, 0xf3, 0xd9, 0x5d, 0x82, 0x12, 
+  0xd7, 0xf2, 0x32, 0xd5, 0x33, 0x3d, 0x4f, 0x25, 
+  0x2d, 0x32, 0x72, 0xd3, 0x17, 0x10, 0x18, 
+
+ /* Char 61 is 14px wide @ 531 */
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+  0x03, 0x0e, 0x92, 0x32, 0x01, 0x91, 
+
+ /* Char 62 is 14px wide @ 537 */
+ /*        *       *           */ 
+ /*       **       **          */ 
+ /*        **     **           */ 
+ /*        **     **           */ 
+ /*        ***   ***           */ 
+ /*         **   **            */ 
+ /*         **   **            */ 
+ /*          ** **             */ 
+ /*          *****             */ 
+ /*           ***              */ 
+ /*           ***              */ 
+ /*            *               */ 
+  0x01, 0x51, 0x71, 0xd3, 0x27, 0x2d, 0x3f, 0x25, 
+  0x2d, 0x43, 0x33, 0xd5, 0xf2, 0x32, 0xd7, 0x21, 
+  0x2d, 0x85, 0xd9, 0xf3, 0xdb, 0x10, 0x1c, 
+
+ /* Char 63 is 10px wide @ 560 */
+ /*                    *       */ 
+ /*                   ***      */ 
+ /*     ***  ***       **      */ 
+ /*     ***  ****      **      */ 
+ /*            ***     **      */ 
+ /*              **   ***      */ 
+ /*               ******       */ 
+ /*                ****        */ 
+  0x02, 0x11, 0xdb, 0x39, 0x32, 0x37, 0x29, 0x32, 
+  0x46, 0x2d, 0x33, 0x52, 0xd5, 0x23, 0x3d, 0x66, 
+  0xd8, 0x40, 0x15, 
+
+ /* Char 64 is 23px wide @ 579 */
+ /*        *******             */ 
+ /*      ***********           */ 
+ /*    *****     *****         */ 
+ /*   ****          ***        */ 
+ /*   **             **        */ 
+ /*  **     *****     **       */ 
+ /*  **   ********    **       */ 
+ /* ***   ***   ***    **      */ 
+ /* **   ***     ***   **      */ 
+ /* **   **       **   **      */ 
+ /* **   **       **   **      */ 
+ /* **   **       **   **      */ 
+ /* **   ***********  ***      */ 
+ /* **   ***********  **       */ 
+ /*      **          ***       */ 
+ /*      **         ***        */ 
+ /*      ****     ****         */ 
+ /*       ***********          */ 
+ /*         *******            */ 
+  0x02, 0xf7, 0xd4, 0xbd, 0x05, 0x55, 0xa4, 0xa3, 
+  0x92, 0xd0, 0x28, 0x25, 0x55, 0x27, 0x23, 0x84, 
+  0x26, 0x33, 0x33, 0x34, 0x25, 0x23, 0x35, 0x33, 
+  0x25, 0x23, 0xe1, 0x27, 0x23, 0x25, 0x23, 0xb2, 
+  0x35, 0x23, 0xb2, 0x2b, 0x2a, 0x3b, 0x29, 0x3c, 
+  0x45, 0x4d, 0x1b, 0xd4, 0x70, 0x33, 
+
+ /* Char 65 is 17px wide @ 625 */
+ /*     *                      */ 
+ /*     ****                   */ 
+ /*      ******                */ 
+ /*        ******              */ 
+ /*         ********           */ 
+ /*         **   *****         */ 
+ /*         **     ******      */ 
+ /*         **       ****      */ 
+ /*         **     ******      */ 
+ /*         **   *****         */ 
+ /*         ********           */ 
+ /*        ******              */ 
+ /*      ******                */ 
+ /*     ****                   */ 
+ /*     *                      */ 
+  0x41, 0xdc, 0x4d, 0xa6, 0xd9, 0x6d, 0x88, 0xd5, 
+  0x23, 0x5d, 0x32, 0x56, 0xd0, 0x27, 0x4d, 0x02, 
+  0x56, 0xd0, 0x23, 0x5d, 0x38, 0xd4, 0x6d, 0x56, 
+  0xd6, 0x4d, 0x91, 0x03, 0xd1, 
+
+ /* Char 66 is 16px wide @ 654 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      ***   ***      */ 
+ /*      **    ****   **       */ 
+ /*      ***  *** ******       */ 
+ /*       ******   ****        */ 
+ /*        ****                */ 
+  0x02, 0xcf, 0xd4, 0x9e, 0x32, 0x62, 0x52, 0x92, 
+  0x63, 0x33, 0xa2, 0x44, 0x32, 0xb3, 0x23, 0x16, 
+  0xc6, 0x34, 0xd1, 0x40, 0x37, 
+
+ /* Char 67 is 16px wide @ 675 */
+ /*          *******           */ 
+ /*        ***********         */ 
+ /*       ****     ****        */ 
+ /*      ***         ***       */ 
+ /*      **           **       */ 
+ /*     ***           ***      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     ***           ***      */ 
+ /*      **           **       */ 
+  0x01, 0x77, 0xd4, 0xbd, 0x14, 0x54, 0xc3, 0x93, 
+  0xb2, 0xb2, 0xa3, 0xb3, 0x9e, 0x32, 0xd0, 0x29, 
+  0x3b, 0x3a, 0x2b, 0x20, 0x2e, 
+
+ /* Char 68 is 17px wide @ 696 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*      **           **       */ 
+ /*      **           **       */ 
+ /*       **         **        */ 
+ /*       ****     ****        */ 
+ /*         *********          */ 
+ /*          *******           */ 
+  0x02, 0xcf, 0xd4, 0x9e, 0x42, 0xd0, 0x2a, 0xf2, 
+  0xb2, 0xc2, 0x92, 0xd0, 0x45, 0x4d, 0x29, 0xd5, 
+  0x70, 0x18, 
+
+ /* Char 69 is 14px wide @ 714 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **      **     **      */ 
+ /*     **                     */ 
+  0x02, 0xcf, 0xd4, 0x9e, 0x62, 0x62, 0x52, 0x92, 
+  0x02, 0x21, 
+
+ /* Char 70 is 13px wide @ 724 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*             **     **      */ 
+ /*             **     **      */ 
+ /*             **     **      */ 
+ /*             **     **      */ 
+ /*             **     **      */ 
+ /*             **     **      */ 
+ /*             **     **      */ 
+ /*                    **      */ 
+  0x02, 0xcf, 0xd4, 0xd4, 0xe5, 0x25, 0x2d, 0xb2, 
+  0x01, 0x31, 
+
+ /* Char 71 is 17px wide @ 734 */
+ /*          *******           */ 
+ /*        ***********         */ 
+ /*       ****     ****        */ 
+ /*      ***         ***       */ 
+ /*      **           **       */ 
+ /*     ***           ***      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     ********      ***      */ 
+ /*      *******      **       */ 
+  0x01, 0x77, 0xd4, 0xbd, 0x14, 0x54, 0xc3, 0x93, 
+  0xb2, 0xb2, 0xa3, 0xb3, 0x9e, 0x32, 0xd0, 0x29, 
+  0x86, 0x3a, 0x76, 0x20, 0x48, 
+
+ /* Char 72 is 17px wide @ 755 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*             **             */ 
+ /*             **             */ 
+ /*             **             */ 
+ /*             **             */ 
+ /*             **             */ 
+ /*             **             */ 
+ /*             **             */ 
+ /*             **             */ 
+ /*             **             */ 
+ /*     *****************      */ 
+ /*     *****************      */ 
+  0x02, 0xcf, 0xd4, 0xd4, 0xe7, 0x2d, 0x3f, 0xd4, 
+  0x02, 0xd1, 
+
+ /* Char 73 is 7px wide @ 765 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+  0x02, 0xcf, 0xd4, 0x04, 0x71, 
+
+ /* Char 74 is 13px wide @ 770 */
+ /*      *                     */ 
+ /*     ***                    */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     ***                    */ 
+ /*      ***                   */ 
+ /*      ****************      */ 
+ /*        **************      */ 
+  0x51, 0xdb, 0x3d, 0xae, 0x22, 0xdb, 0x3d, 0xb3, 
+  0xda, 0xd3, 0xcd, 0x10, 0x47, 
+
+ /* Char 75 is 16px wide @ 783 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*             ***            */ 
+ /*            ****            */ 
+ /*           *** **           */ 
+ /*          ***   **          */ 
+ /*         ****    **         */ 
+ /*        ****      **        */ 
+ /*       ****        **       */ 
+ /*      ****          **      */ 
+ /*     ****            *      */ 
+ /*     **              *      */ 
+ /*     *                      */ 
+  0x02, 0xcf, 0xd4, 0xd4, 0x3d, 0x94, 0xd8, 0x31, 
+  0x2d, 0x63, 0x32, 0xd4, 0x44, 0x2d, 0x24, 0x62, 
+  0xd0, 0x48, 0x2b, 0x4a, 0x29, 0x4c, 0x19, 0x2d, 
+  0x11, 0x91, 0x02, 0x31, 
+
+ /* Char 76 is 13px wide @ 811 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+  0x02, 0xcf, 0xd4, 0x9e, 0x62, 0x02, 0x21, 
+
+ /* Char 77 is 22px wide @ 818 */
+ /*     ***********            */ 
+ /*     *****************      */ 
+ /*              ********      */ 
+ /*                 ****       */ 
+ /*               ****         */ 
+ /*             ****           */ 
+ /*          *****             */ 
+ /*        *****               */ 
+ /*       ***                  */ 
+ /*       ***                  */ 
+ /*        *****               */ 
+ /*           ****             */ 
+ /*             ****           */ 
+ /*               ****         */ 
+ /*                 ****       */ 
+ /*              ********      */ 
+ /*     *****************      */ 
+ /*     **********             */ 
+  0x01, 0x2b, 0xd2, 0xd4, 0xd5, 0x8d, 0x84, 0xd7, 
+  0x4d, 0x74, 0xd6, 0x5d, 0x65, 0xd7, 0xf3, 0xdb, 
+  0x5d, 0xb4, 0xdb, 0x4d, 0xb4, 0xdb, 0x4d, 0x68, 
+  0x9d, 0x49, 0xa0, 0x4e, 
+
+ /* Char 78 is 18px wide @ 846 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*                  ***       */ 
+ /*                ****        */ 
+ /*               ****         */ 
+ /*              ***           */ 
+ /*             ***            */ 
+ /*           ****             */ 
+ /*          ***               */ 
+ /*         ***                */ 
+ /*       ***                  */ 
+ /*      ****************      */ 
+ /*     *****************      */ 
+  0x02, 0xcf, 0xd4, 0xd9, 0x3d, 0x84, 0xd8, 0x4d, 
+  0x83, 0xd9, 0x3d, 0x84, 0xd8, 0x3d, 0x93, 0xd8, 
+  0x3d, 0x9d, 0x39, 0xd4, 0x04, 0x71, 
+
+ /* Char 79 is 19px wide @ 868 */
+ /*          *******           */ 
+ /*        ***********         */ 
+ /*       ****     ****        */ 
+ /*      ***         ***       */ 
+ /*      **           **       */ 
+ /*     ***           ***      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     ***           ***      */ 
+ /*      **           **       */ 
+ /*      ***         ***       */ 
+ /*       ****     ****        */ 
+ /*        ***********         */ 
+ /*          *******           */ 
+  0x01, 0x77, 0xd4, 0xbd, 0x14, 0x54, 0xc3, 0x93, 
+  0xb2, 0xb2, 0xa3, 0xb3, 0x9e, 0x22, 0xd0, 0x29, 
+  0x3b, 0x3a, 0x2b, 0x2b, 0x39, 0x3c, 0x45, 0x4d, 
+  0x1b, 0xd4, 0x70, 0x32, 
+
+ /* Char 80 is 15px wide @ 896 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*           **       **      */ 
+ /*           **       **      */ 
+ /*           **       **      */ 
+ /*           **       **      */ 
+ /*           **       **      */ 
+ /*           ***      **      */ 
+ /*            **     **       */ 
+ /*            ***   ***       */ 
+ /*             *******        */ 
+ /*              *****         */ 
+  0x02, 0xcf, 0xd4, 0xd2, 0xe3, 0x27, 0x2d, 0x23, 
+  0x62, 0xd3, 0x25, 0x2d, 0x43, 0x33, 0xd5, 0x7d, 
+  0x75, 0x01, 0x61, 
+
+ /* Char 81 is 19px wide @ 915 */
+ /*          *******           */ 
+ /*         *********          */ 
+ /*       ****     ****        */ 
+ /*       **         **        */ 
+ /*      **           **       */ 
+ /*     ***           ***      */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*    ***             **      */ 
+ /*   ****             **      */ 
+ /*  *****             **      */ 
+ /*  **  **           ***      */ 
+ /* ***  **           **       */ 
+ /* **    **         **        */ 
+ /* **    ****     ****        */ 
+ /*         *********          */ 
+ /*          ******            */ 
+  0x01, 0x77, 0xd5, 0x9d, 0x24, 0x54, 0xd0, 0x29, 
+  0x2c, 0x2b, 0x2a, 0x3b, 0x39, 0xf2, 0xd0, 0x28, 
+  0x3d, 0x02, 0x74, 0xd0, 0x26, 0x5d, 0x02, 0x62, 
+  0x22, 0xb3, 0x53, 0x22, 0xb2, 0x62, 0x42, 0x92, 
+  0x72, 0x44, 0x54, 0xd2, 0x9d, 0x56, 0x01, 0x91, 
+
+
+ /* Char 82 is 16px wide @ 955 */
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*            **      **      */ 
+ /*            **      **      */ 
+ /*            **      **      */ 
+ /*            **      **      */ 
+ /*            **      **      */ 
+ /*           ***      **      */ 
+ /*         ******    **       */ 
+ /*        ***  ***  ***       */ 
+ /*      ****    ******        */ 
+ /*     ***       ****         */ 
+ /*     **                     */ 
+  0x02, 0xcf, 0xd4, 0xd3, 0xe3, 0x26, 0x2d, 0x23, 
+  0x62, 0xd0, 0x64, 0x2d, 0x03, 0x23, 0x23, 0xb4, 
+  0x46, 0xb3, 0x74, 0xc2, 0x02, 0x21, 
+
+ /* Char 83 is 13px wide @ 977 */
+ /*      **        ****        */ 
+ /*     ***       ******       */ 
+ /*     **       ***  **       */ 
+ /*     **       **    **      */ 
+ /*     **      ***    **      */ 
+ /*     **      **     **      */ 
+ /*     **     **      **      */ 
+ /*     ***    **      **      */ 
+ /*      ***  **      ***      */ 
+ /*      *******       *       */ 
+ /*       ****                 */ 
+  0x01, 0x32, 0x84, 0xb3, 0x76, 0xa2, 0x73, 0x22, 
+  0xa2, 0x72, 0x42, 0x92, 0x63, 0x42, 0x92, 0x62, 
+  0x52, 0x92, 0x52, 0x62, 0x93, 0x42, 0x62, 0xa3, 
+  0x22, 0x63, 0xa7, 0x71, 0xc4, 0x01, 0xe1, 
+
+ /* Char 84 is 14px wide @ 1008 */
+ /*                    **      */ 
+ /*                    **      */ 
+ /*                    **      */ 
+ /*                    **      */ 
+ /*                    **      */ 
+ /*     *****************      */ 
+ /*     *****************      */ 
+ /*                    **      */ 
+ /*                    **      */ 
+ /*                    **      */ 
+ /*                    **      */ 
+ /*                    **      */ 
+  0xd6, 0xe3, 0x29, 0xfd, 0x4d, 0xbe, 0x32, 0x02, 
+  0xd1, 
+
+ /* Char 85 is 17px wide @ 1017 */
+ /*         *************      */ 
+ /*       ***************      */ 
+ /*      ***                   */ 
+ /*      **                    */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*      **                    */ 
+ /*      ***                   */ 
+ /*       ***************      */ 
+ /*         *************      */ 
+  0x03, 0x0d, 0x0b, 0xd2, 0xa3, 0xda, 0x2d, 0xae, 
+  0x32, 0xdc, 0x2d, 0xb3, 0xdb, 0xd2, 0xd0, 0xd0, 
+  0x02, 0xd1, 
+
+ /* Char 86 is 16px wide @ 1035 */
+ /*                    **      */ 
+ /*                 *****      */ 
+ /*               ******       */ 
+ /*            ******          */ 
+ /*          *****             */ 
+ /*       ******               */ 
+ /*     *****                  */ 
+ /*     ***                    */ 
+ /*     ****                   */ 
+ /*      *****                 */ 
+ /*        ******              */ 
+ /*          ******            */ 
+ /*             ******         */ 
+ /*               ******       */ 
+ /*                  ****      */ 
+ /*                    **      */ 
+  0xd6, 0x2d, 0x85, 0xd6, 0x6d, 0x46, 0xd5, 0x5d, 
+  0x56, 0xd5, 0x5d, 0x83, 0xda, 0x4d, 0xa5, 0xda, 
+  0x6d, 0x96, 0xda, 0x6d, 0x96, 0xda, 0x4d, 0xb2, 
+  0x51, 
+
+ /* Char 87 is 23px wide @ 1060 */
+ /*                   ***      */ 
+ /*              ********      */ 
+ /*           *********        */ 
+ /*       *********            */ 
+ /*     *******                */ 
+ /*     ****                   */ 
+ /*     ******                 */ 
+ /*        *****               */ 
+ /*          ******            */ 
+ /*             ******         */ 
+ /*                ****        */ 
+ /*             *******        */ 
+ /*          *******           */ 
+ /*       *******              */ 
+ /*     ******                 */ 
+ /*     ****                   */ 
+ /*     *******                */ 
+ /*       *********            */ 
+ /*           *********        */ 
+ /*               *******      */ 
+ /*                   ***      */ 
+  0x02, 0x03, 0xd5, 0x8d, 0x29, 0xd0, 0x9d, 0x27, 
+  0xd6, 0x4d, 0x96, 0xda, 0x5d, 0xa6, 0xda, 0x6d, 
+  0xa4, 0xd6, 0x7d, 0x37, 0xd3, 0x7d, 0x46, 0xd7, 
+  0x4d, 0x97, 0xd8, 0x9d, 0x89, 0xd8, 0x7d, 0xa3, 
+  0x01, 0x31, 
+
+ /* Char 88 is 16px wide @ 1094 */
+ /*     *               *      */ 
+ /*     **             **      */ 
+ /*     ****         ****      */ 
+ /*       ***       ***        */ 
+ /*        ****   ****         */ 
+ /*          *** ***           */ 
+ /*           *****            */ 
+ /*           *****            */ 
+ /*          *** ***           */ 
+ /*        ****   ****         */ 
+ /*       ***       ***        */ 
+ /*     ****         ****      */ 
+ /*     **             **      */ 
+ /*     *               *      */ 
+  0x01, 0x21, 0xd2, 0x19, 0x2d, 0x02, 0x94, 0x94, 
+  0xb3, 0x73, 0xd1, 0x43, 0x4d, 0x43, 0x13, 0xd7, 
+  0xf5, 0xd7, 0x31, 0x3d, 0x44, 0x34, 0xd1, 0x37, 
+  0x3b, 0x49, 0x49, 0x2d, 0x02, 0x91, 0xd2, 0x10, 
+  0x13, 
+
+ /* Char 89 is 14px wide @ 1127 */
+ /*                     *      */ 
+ /*                   ***      */ 
+ /*                  ****      */ 
+ /*                ****        */ 
+ /*              ****          */ 
+ /*             ***            */ 
+ /*     **********             */ 
+ /*     **********             */ 
+ /*             ***            */ 
+ /*              ****          */ 
+ /*                ****        */ 
+ /*                  ****      */ 
+ /*                   ***      */ 
+ /*                     *      */ 
+  0xd7, 0x1d, 0xa3, 0xd9, 0x4d, 0x74, 0xd7, 0x4d, 
+  0x83, 0xd2, 0xfa, 0xdb, 0x3d, 0xb4, 0xdb, 0x4d, 
+  0xb4, 0xda, 0x3d, 0xc1, 0x51, 
+
+ /* Char 90 is 14px wide @ 1148 */
+ /*     ***            **      */ 
+ /*     ****           **      */ 
+ /*     ******         **      */ 
+ /*     **  ***        **      */ 
+ /*     **   ****      **      */ 
+ /*     **     ***     **      */ 
+ /*     **      ***    **      */ 
+ /*     **       ***   **      */ 
+ /*     **         *** **      */ 
+ /*     **          *****      */ 
+ /*     **           ****      */ 
+ /*     **            ***      */ 
+  0x01, 0x23, 0xc2, 0x94, 0xb2, 0x96, 0x92, 0x92, 
+  0x23, 0x82, 0x92, 0x34, 0x62, 0x92, 0x53, 0x52, 
+  0x92, 0x63, 0x42, 0x92, 0x73, 0x32, 0x92, 0x93, 
+  0x12, 0x92, 0xa5, 0x92, 0xb4, 0x92, 0xc3, 0x01, 
+  0x31, 
+
+ /* Char 91 is 9px wide @ 1181 */
+ /* ***********************    */ 
+ /* ***********************    */ 
+ /* **                   **    */ 
+ /* **                   **    */ 
+ /* **                   **    */ 
+ /* **                   **    */ 
+  0x02, 0x8d, 0xaf, 0x32, 0xd6, 0xe2, 0x20, 0x11, 
+
+
+ /* Char 92 is 10px wide @ 1189 */
+ /*                    ****    */ 
+ /*                 ******     */ 
+ /*               *****        */ 
+ /*            ******          */ 
+ /*          *****             */ 
+ /*       ******               */ 
+ /*     *****                  */ 
+ /*  ******                    */ 
+ /* ****                       */ 
+ /* *                          */ 
+  0xd6, 0x4d, 0x66, 0xd5, 0x5d, 0x56, 0xd5, 0x5d, 
+  0x56, 0xd5, 0x5d, 0x56, 0xd6, 0x4d, 0x91, 0xdc, 
+
+
+ /* Char 93 is 9px wide @ 1205 */
+ /* **                   **    */ 
+ /* **                   **    */ 
+ /* **                   **    */ 
+ /* **                   **    */ 
+ /* ***********************    */ 
+ /* ***********************    */ 
+  0xe2, 0xd6, 0xe2, 0x23, 0xda, 0xf0, 0x45, 
+
+ /* Char 94 is 14px wide @ 1212 */
+ /*              *             */ 
+ /*             ***            */ 
+ /*              ****          */ 
+ /*                ****        */ 
+ /*                  ***       */ 
+ /*                   ***      */ 
+ /*                  ***       */ 
+ /*                ****        */ 
+ /*              ****          */ 
+ /*             ***            */ 
+ /*              *             */ 
+  0x01, 0xb1, 0xdb, 0x3d, 0xb4, 0xdb, 0x4d, 0xb3, 
+  0xdb, 0x3d, 0x93, 0xd8, 0x4d, 0x74, 0xd8, 0x3d, 
+  0xb1, 0x03, 0x41, 
+
+ /* Char 95 is 12px wide @ 1231 */
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+ /* **                         */ 
+  0xe2, 0xe9, 0xdb, 0x2d, 0xb1, 
+
+ /* Char 96 is 9px wide @ 1236 */
+ /*                      *     */ 
+ /*                     ***    */ 
+ /*                    ***     */ 
+ /*                   ***      */ 
+ /*                    *       */ 
+  0x02, 0x31, 0xdb, 0x3d, 0x93, 0xd9, 0x3d, 0xb1, 
+  0x04, 0x81, 
+
+ /* Char 97 is 13px wide @ 1246 */
+ /*       ****                 */ 
+ /*      ******    **          */ 
+ /*     ***  **    **          */ 
+ /*     **    **   **          */ 
+ /*     **    **   **          */ 
+ /*     **    **   **          */ 
+ /*     **    **   **          */ 
+ /*     **    **  ***          */ 
+ /*     ************           */ 
+ /*     ***********            */ 
+  0x01, 0x44, 0xd8, 0x64, 0x2d, 0x03, 0x22, 0x42, 
+  0xd0, 0xe2, 0x24, 0x23, 0x2d, 0x02, 0x42, 0x23, 
+  0xd0, 0xcd, 0x1b, 0x03, 0x31, 
+
+ /* Char 98 is 15px wide @ 1267 */
+ /*     ******************     */ 
+ /*     ******************     */ 
+ /*     **        **           */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*      **       ***          */ 
+ /*      ***     ***           */ 
+ /*       *********            */ 
+ /*         *****              */ 
+  0x02, 0xcf, 0xd5, 0x82, 0x82, 0xd1, 0xe2, 0x29, 
+  0x2d, 0x12, 0x73, 0xd1, 0x35, 0x3d, 0x39, 0xd6, 
+  0x50, 0x35, 
+
+ /* Char 99 is 12px wide @ 1285 */
+ /*         *****              */ 
+ /*       *********            */ 
+ /*      ***     ***           */ 
+ /*      **       **           */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+  0x01, 0x65, 0xd6, 0x9d, 0x33, 0x53, 0xd2, 0x27, 
+  0x2d, 0x1e, 0x42, 0x92, 0x01, 0x71, 
+
+ /* Char 100 is 15px wide @ 1299 */
+ /*         *****              */ 
+ /*       *********            */ 
+ /*      ***     ***           */ 
+ /*      **       ***          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **        **           */ 
+ /*     ******************     */ 
+ /*     ******************     */ 
+  0x01, 0x65, 0xd6, 0x9d, 0x33, 0x53, 0xd2, 0x27, 
+  0x3d, 0x0e, 0x22, 0x92, 0xd0, 0x28, 0x2d, 0x1f, 
+  0xd5, 0x04, 0x61, 
+
+ /* Char 101 is 14px wide @ 1318 */
+ /*         *****              */ 
+ /*       *********            */ 
+ /*      **** ** ***           */ 
+ /*     ***   **  ***          */ 
+ /*     **    **   **          */ 
+ /*     **    **   **          */ 
+ /*     **    **   **          */ 
+ /*     **    **  ***          */ 
+ /*     **    ** ***           */ 
+ /*     **    ******           */ 
+ /*           ****             */ 
+  0x01, 0x65, 0xd6, 0x9d, 0x34, 0x12, 0x13, 0xd1, 
+  0x33, 0x22, 0x3d, 0x0e, 0x12, 0x42, 0x32, 0xd0, 
+  0x24, 0x22, 0x3d, 0x02, 0x42, 0x13, 0xd1, 0x24, 
+  0x6d, 0x74, 0x03, 0x41, 
+
+ /* Char 102 is 10px wide @ 1346 */
+ /*     ****************       */ 
+ /*     *****************      */ 
+ /*                **  ***     */ 
+ /*                **   **     */ 
+ /*                **   **     */ 
+ /*                **   **     */ 
+ /*                     **     */ 
+  0x02, 0xcd, 0x3a, 0xd4, 0xd7, 0x22, 0x3d, 0x6e, 
+  0x12, 0x32, 0xdb, 0x20, 0x12, 
+
+ /* Char 103 is 14px wide @ 1359 */
+ /*        ******              */ 
+ /* **    *********            */ 
+ /* **   ***     ***           */ 
+ /* **  ***       **           */ 
+ /* **  **         **          */ 
+ /* **  **         **          */ 
+ /* **  **         **          */ 
+ /* **  **         **          */ 
+ /*  ******        **          */ 
+ /*  ****************          */ 
+ /*    **************          */ 
+  0x01, 0x56, 0xd0, 0x24, 0x9b, 0x23, 0x35, 0x3a, 
+  0x22, 0x37, 0x2a, 0x22, 0xe2, 0x29, 0x2a, 0x68, 
+  0x2a, 0xd3, 0xcd, 0x10, 0x31, 
+
+ /* Char 104 is 14px wide @ 1380 */
+ /*     ******************     */ 
+ /*     ******************     */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*              ***           */ 
+ /*     ************           */ 
+ /*     **********             */ 
+  0x02, 0xcf, 0xd5, 0xd6, 0xe3, 0x2d, 0x93, 0xd1, 
+  0xcd, 0x1a, 0x03, 0x41, 
+
+ /* Char 105 is 7px wide @ 1392 */
+ /*     *************   **     */ 
+ /*     *************   **     */ 
+  0x02, 0xcf, 0xd0, 0x32, 0x04, 0x61, 
+
+ /* Char 106 is 7px wide @ 1398 */
+ /* **                         */ 
+ /* ***                        */ 
+ /*  ****************   **     */ 
+ /*   ***************   **     */ 
+  0xe2, 0xdb, 0x3d, 0xbd, 0x33, 0x26, 0xd2, 0x32, 
+  0x04, 0x61, 
+
+ /* Char 107 is 13px wide @ 1408 */
+ /*     ******************     */ 
+ /*     ******************     */ 
+ /*           **               */ 
+ /*          ****              */ 
+ /*         ******             */ 
+ /*        **** ***            */ 
+ /*       ****   **            */ 
+ /*      ****     **           */ 
+ /*     ****       **          */ 
+ /*     **          *          */ 
+ /*     *                      */ 
+  0x02, 0xcf, 0xd5, 0xd1, 0x2d, 0xa4, 0xd8, 0x6d, 
+  0x64, 0x13, 0xd4, 0x43, 0x2d, 0x34, 0x52, 0xd1, 
+  0x47, 0x2d, 0x02, 0xa1, 0xd0, 0x1d, 0x81, 
+
+ /* Char 108 is 7px wide @ 1431 */
+ /*       ****************     */ 
+ /*     ******************     */ 
+ /*     ***                    */ 
+ /*     **                     */ 
+  0x02, 0xed, 0x38, 0xd5, 0x83, 0xda, 0x20, 0x22, 
+
+
+ /* Char 109 is 21px wide @ 1439 */
+ /*     *************          */ 
+ /*     *************          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*              ****          */ 
+ /*     ************           */ 
+ /*     ************           */ 
+ /*               ***          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*              ****          */ 
+ /*     ************           */ 
+ /*     **********             */ 
+  0x02, 0xcf, 0xd0, 0xdb, 0xe3, 0x2d, 0x94, 0xd0, 
+  0xfc, 0xdb, 0x3d, 0xbe, 0x22, 0xd9, 0x4d, 0x0c, 
+  0xd1, 0xa0, 0x1a, 
+
+ /* Char 110 is 14px wide @ 1458 */
+ /*     *************          */ 
+ /*     *************          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*              ***           */ 
+ /*     ************           */ 
+ /*     **********             */ 
+  0x02, 0xcf, 0xd0, 0xdb, 0xe3, 0x2d, 0x93, 0xd1, 
+  0xcd, 0x1a, 0x03, 0x41, 
+
+ /* Char 111 is 15px wide @ 1470 */
+ /*         *****              */ 
+ /*       *********            */ 
+ /*      ***     ***           */ 
+ /*     ***       **           */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     ***       **           */ 
+ /*      ***     ***           */ 
+ /*       *********            */ 
+ /*         *****              */ 
+  0x01, 0x65, 0xd6, 0x9d, 0x33, 0x53, 0xd1, 0x37, 
+  0x2d, 0x1e, 0x22, 0x92, 0xd0, 0x37, 0x2d, 0x23, 
+  0x53, 0xd3, 0x9d, 0x65, 0x03, 0x51, 
+
+ /* Char 112 is 15px wide @ 1492 */
+ /* *****************          */ 
+ /* *****************          */ 
+ /*      **        **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     ***       **           */ 
+ /*      ***     ***           */ 
+ /*       *********            */ 
+ /*         *****              */ 
+  0x02, 0x8d, 0x4f, 0xd1, 0x28, 0x2d, 0x0e, 0x22, 
+  0x92, 0xd0, 0x37, 0x2d, 0x23, 0x53, 0xd3, 0x9d, 
+  0x65, 0x03, 0x51, 
+
+ /* Char 113 is 15px wide @ 1511 */
+ /*         *****              */ 
+ /*       *********            */ 
+ /*      ***     ***           */ 
+ /*     ***       **           */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*      **        **          */ 
+ /* *****************          */ 
+ /* *****************          */ 
+  0x01, 0x65, 0xd6, 0x9d, 0x33, 0x53, 0xd1, 0x37, 
+  0x2d, 0x1e, 0x22, 0x92, 0xd1, 0x28, 0x29, 0xd4, 
+  0xf0, 0x4b, 
+
+ /* Char 114 is 10px wide @ 1529 */
+ /*     ************           */ 
+ /*     *************          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+ /*                **          */ 
+  0x02, 0xcc, 0xd1, 0xd0, 0xdb, 0xe3, 0x20, 0x17, 
+
+
+ /* Char 115 is 11px wide @ 1537 */
+ /*     **      ***            */ 
+ /*     **     *****           */ 
+ /*     **    *** **           */ 
+ /*     **    **   **          */ 
+ /*     **   ***   **          */ 
+ /*     **   **    **          */ 
+ /*     *** ***    **          */ 
+ /*      *****     **          */ 
+ /*       ***                  */ 
+  0x01, 0x22, 0x63, 0xd2, 0x25, 0x5d, 0x12, 0x43, 
+  0x12, 0xd1, 0x24, 0x23, 0x2d, 0x02, 0x33, 0x32, 
+  0xd0, 0x23, 0x24, 0x2d, 0x03, 0x13, 0x42, 0xd1, 
+  0x55, 0x2d, 0x23, 0x01, 0xf1, 
+
+ /* Char 116 is 10px wide @ 1566 */
+ /*       ***************      */ 
+ /*      ****************      */ 
+ /*     ***        **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+  0x02, 0xed, 0x2a, 0xd3, 0x93, 0x82, 0xd0, 0xe2, 
+  0x29, 0x20, 0x17, 
+
+ /* Char 117 is 14px wide @ 1577 */
+ /*        **********          */ 
+ /*      ************          */ 
+ /*      ***                   */ 
+ /*     ***                    */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     *************          */ 
+ /*     *************          */ 
+  0x02, 0xfa, 0xd1, 0xcd, 0x13, 0xd9, 0x3d, 0xae, 
+  0x22, 0xdb, 0xfd, 0x00, 0x31, 
+
+ /* Char 118 is 12px wide @ 1590 */
+ /*                **          */ 
+ /*             *****          */ 
+ /*           ******           */ 
+ /*        ******              */ 
+ /*      *****                 */ 
+ /*     ****                   */ 
+ /*     ****                   */ 
+ /*      *****                 */ 
+ /*        ******              */ 
+ /*           ******           */ 
+ /*             *****          */ 
+ /*                **          */ 
+  0xd2, 0x2d, 0x85, 0xd6, 0x6d, 0x46, 0xd5, 0x5d, 
+  0x7f, 0x4d, 0xa5, 0xda, 0x6d, 0xa6, 0xd9, 0x5d, 
+  0xb2, 0x91, 
+
+ /* Char 119 is 19px wide @ 1608 */
+ /*                **          */ 
+ /*             *****          */ 
+ /*          *******           */ 
+ /*       ******               */ 
+ /*     *****                  */ 
+ /*     ****                   */ 
+ /*     ******                 */ 
+ /*       *******              */ 
+ /*          *******           */ 
+ /*             *****          */ 
+ /*          ********          */ 
+ /*       *******              */ 
+ /*     ******                 */ 
+ /*     ****                   */ 
+ /*     *****                  */ 
+ /*       ******               */ 
+ /*          *******           */ 
+ /*             *****          */ 
+ /*                **          */ 
+  0xd2, 0x2d, 0x85, 0xd5, 0x7d, 0x36, 0xd5, 0x5d, 
+  0x84, 0xd9, 0x6d, 0x97, 0xd9, 0x7d, 0x95, 0xd5, 
+  0x8d, 0x27, 0xd4, 0x6d, 0x74, 0xd9, 0x5d, 0xa6, 
+  0xda, 0x7d, 0x95, 0xdb, 0x29, 
+
+ /* Char 120 is 13px wide @ 1637 */
+ /*     *           *          */ 
+ /*     **         **          */ 
+ /*     ****      ***          */ 
+ /*       ***   ***            */ 
+ /*        *** ***             */ 
+ /*         *****              */ 
+ /*         *****              */ 
+ /*        *** ***             */ 
+ /*       ***   ***            */ 
+ /*     ****      ***          */ 
+ /*     **         **          */ 
+ /*     *           *          */ 
+  0x41, 0xb1, 0xd0, 0x29, 0x2d, 0x04, 0x63, 0xd2, 
+  0x33, 0x3d, 0x53, 0x13, 0xd7, 0xf5, 0xd7, 0x31, 
+  0x3d, 0x53, 0x33, 0xd2, 0x46, 0x3d, 0x02, 0x92, 
+  0xd0, 0x1b, 0x10, 0x17, 
+
+ /* Char 121 is 12px wide @ 1665 */
+ /* **             **          */ 
+ /* **          *****          */ 
+ /* **       *******           */ 
+ /* ***   *******              */ 
+ /*  *********                 */ 
+ /*   ******                   */ 
+ /*     ******                 */ 
+ /*        ******              */ 
+ /*           ******           */ 
+ /*              ****          */ 
+ /*                **          */ 
+  0xe2, 0xd0, 0x29, 0x2a, 0x59, 0x27, 0x7a, 0x33, 
+  0x7d, 0x19, 0xd5, 0x6d, 0x96, 0xda, 0x6d, 0xa6, 
+  0xda, 0x4d, 0xb2, 0x01, 0x71, 
+
+ /* Char 122 is 12px wide @ 1686 */
+ /*     ***        **          */ 
+ /*     ****       **          */ 
+ /*     ******     **          */ 
+ /*     **  ***    **          */ 
+ /*     **   ***   **          */ 
+ /*     **     *** **          */ 
+ /*     **      *****          */ 
+ /*     **       ****          */ 
+ /*     **        ***          */ 
+  0x01, 0x23, 0x82, 0xd0, 0x47, 0x2d, 0x06, 0x52, 
+  0xd0, 0x22, 0x34, 0x2d, 0x02, 0x33, 0x32, 0xd0, 
+  0x25, 0x31, 0x2d, 0x02, 0x65, 0xd0, 0x27, 0x4d, 
+  0x02, 0x83, 0x03, 0x11, 
+
+ /* Char 123 is 9px wide @ 1714 */
+ /*           **               */ 
+ /*          ****              */ 
+ /*   *******************      */ 
+ /*  *********   *********     */ 
+ /* ***                 ***    */ 
+ /* **                   **    */ 
+ /* **                   **    */ 
+  0x01, 0x82, 0xda, 0x4d, 0x2d, 0x66, 0x93, 0x94, 
+  0x3d, 0x43, 0x32, 0xd6, 0xf2, 0x01, 0x11, 
+
+ /* Char 124 is 7px wide @ 1729 */
+ /* ***********************    */ 
+ /* ***********************    */ 
+  0x02, 0x8d, 0xaf, 0x04, 0x51, 
+
+ /* Char 125 is 9px wide @ 1734 */
+ /* **                   **    */ 
+ /* **                   **    */ 
+ /* ***                 ***    */ 
+ /*  *********   *********     */ 
+ /*   *******************      */ 
+ /*          ****              */ 
+ /*           **               */ 
+  0xe2, 0xd6, 0xf2, 0x33, 0xd4, 0x34, 0x93, 0x96, 
+  0xd6, 0xd1, 0x4d, 0xa2, 0x03, 0x61, 
+
+ /* Char 126 is 14px wide @ 1748 */
+ /*          **                */ 
+ /*          ***               */ 
+ /*           ***              */ 
+ /*            **              */ 
+ /*            **              */ 
+ /*           **               */ 
+ /*          **                */ 
+ /*          **                */ 
+ /*          ***               */ 
+ /*           ***              */ 
+ /*            **              */ 
+  0x01, 0x72, 0xdb, 0x3d, 0xb3, 0xdb, 0xf2, 0xda, 
+  0x2d, 0xaf, 0x2d, 0xb3, 0xdb, 0x3d, 0xb2, 0x03, 
+  0x51, 
+
+ /* Char 196 is 17px wide @ 1765 */
+ /*     *                      */ 
+ /*     ****                   */ 
+ /*      ******                */ 
+ /*        ******          *** */ 
+ /*         ********       *** */ 
+ /*         **   *****     *** */ 
+ /*         **     ******      */ 
+ /*         **       ****      */ 
+ /*         **     ******  *** */ 
+ /*         **   *****     *** */ 
+ /*         ********       *** */ 
+ /*        ******              */ 
+ /*      ******                */ 
+ /*     ****                   */ 
+ /*     *                      */ 
+  0x41, 0xdc, 0x4d, 0xa6, 0xd9, 0x6a, 0x38, 0x87, 
+  0x38, 0x23, 0x55, 0x38, 0x25, 0x6d, 0x02, 0x74, 
+  0xd0, 0x25, 0x62, 0x38, 0x23, 0x55, 0x38, 0x87, 
+  0x37, 0x6d, 0x56, 0xd6, 0x4d, 0x91, 0x03, 0xd1, 
+
+
+ /* Char 214 is 19px wide @ 1797 */
+ /*          *******           */ 
+ /*        ***********         */ 
+ /*       ****     ****        */ 
+ /*      ***         ***       */ 
+ /*      **           **   *** */ 
+ /*     ***           ***  *** */ 
+ /*     **             **  *** */ 
+ /*     **             **      */ 
+ /*     **             **      */ 
+ /*     **             **  *** */ 
+ /*     ***           ***  *** */ 
+ /*      **           **   *** */ 
+ /*      ***         ***       */ 
+ /*       ****     ****        */ 
+ /*        ***********         */ 
+ /*          *******           */ 
+  0x01, 0x77, 0xd4, 0xbd, 0x14, 0x54, 0xc3, 0x93, 
+  0xb2, 0xb2, 0x33, 0x43, 0xb3, 0x23, 0x42, 0xd0, 
+  0x22, 0x34, 0xf2, 0xd0, 0x29, 0x2d, 0x02, 0x23, 
+  0x43, 0xb3, 0x23, 0x52, 0xb2, 0x33, 0x53, 0x93, 
+  0xc4, 0x54, 0xd1, 0xbd, 0x47, 0x03, 0x21, 
+
+ /* Char 220 is 17px wide @ 1836 */
+ /*         *************      */ 
+ /*       ***************      */ 
+ /*      ***               *** */ 
+ /*      **                *** */ 
+ /*     **                 *** */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **                 *** */ 
+ /*     **                 *** */ 
+ /*      **                *** */ 
+ /*      ***                   */ 
+ /*       ***************      */ 
+ /*         *************      */ 
+  0x03, 0x0d, 0x0b, 0xd2, 0xa3, 0xd2, 0x35, 0x2d, 
+  0x33, 0x42, 0xd4, 0x34, 0xf2, 0xdb, 0xf2, 0xd4, 
+  0x35, 0x2d, 0x33, 0x53, 0xdb, 0xd2, 0xd0, 0xd0, 
+  0x02, 0xd1, 
+
+ /* Char 223 is 16px wide @ 1862 */
+ /*     ***************        */ 
+ /*     *****************      */ 
+ /*                   ***      */ 
+ /*                    ***     */ 
+ /*     **     ***      **     */ 
+ /*     **     ****     **     */ 
+ /*     **    *** **    **     */ 
+ /*     **    **   **  ***     */ 
+ /*     **   ***    *****      */ 
+ /*     ***  ***     ***       */ 
+ /*      ******                */ 
+ /*       ****                 */ 
+  0x02, 0xcd, 0x2b, 0xd4, 0xda, 0x3d, 0xb3, 0x82, 
+  0x53, 0x62, 0x82, 0x54, 0x52, 0x82, 0x43, 0x12, 
+  0x42, 0x82, 0x42, 0x32, 0x23, 0x82, 0x33, 0x45, 
+  0x93, 0x23, 0x53, 0xb6, 0xd8, 0x40, 0x38, 
+
+ /* Char 228 is 13px wide @ 1893 */
+ /*       ****                 */ 
+ /*      ******    **  ***     */ 
+ /*     ***  **    **  ***     */ 
+ /*     **    **   **  ***     */ 
+ /*     **    **   **          */ 
+ /*     **    **   **          */ 
+ /*     **    **   **  ***     */ 
+ /*     **    **  ***  ***     */ 
+ /*     ************   ***     */ 
+ /*     ***********            */ 
+  0x01, 0x44, 0xd8, 0x64, 0x22, 0x38, 0x32, 0x24, 
+  0x22, 0x38, 0x24, 0x23, 0x22, 0x38, 0xf2, 0x42, 
+  0x32, 0xd0, 0x24, 0x23, 0x22, 0x38, 0x24, 0x22, 
+  0x32, 0x38, 0xc3, 0x38, 0xb0, 0x33, 
+
+ /* Char 246 is 15px wide @ 1923 */
+ /*         *****              */ 
+ /*       *********            */ 
+ /*      ***     ***   ***     */ 
+ /*     ***       **   ***     */ 
+ /*     **         **  ***     */ 
+ /*     **         **          */ 
+ /*     **         **          */ 
+ /*     **         **  ***     */ 
+ /*     ***       **   ***     */ 
+ /*      ***     ***   ***     */ 
+ /*       *********            */ 
+ /*         *****              */ 
+  0x01, 0x65, 0xd6, 0x9d, 0x33, 0x53, 0x33, 0x83, 
+  0x72, 0x33, 0x82, 0x92, 0x23, 0x8f, 0x29, 0x2d, 
+  0x02, 0x92, 0x23, 0x83, 0x72, 0x33, 0x93, 0x53, 
+  0x33, 0xa9, 0xd6, 0x50, 0x35, 
+
+ /* Char 252 is 14px wide @ 1952 */
+ /*        **********          */ 
+ /*      ************  ***     */ 
+ /*      ***           ***     */ 
+ /*     ***            ***     */ 
+ /*     **                     */ 
+ /*     **                     */ 
+ /*     **             ***     */ 
+ /*     **             ***     */ 
+ /*     *************  ***     */ 
+ /*     *************          */ 
+  0x02, 0xfa, 0xd1, 0xc2, 0x39, 0x3b, 0x38, 0x3c, 
+  0x38, 0xf2, 0xdb, 0xf2, 0xd0, 0x38, 0xd0, 0x23, 
+  0x8d, 0x00, 0x31, 
+
+ /* Char 8364 is 14px wide @ 1971 */
+ /*          **  **            */ 
+ /*          **  **            */ 
+ /*         ********           */ 
+ /*       ************         */ 
+ /*      ******  ******        */ 
+ /*      **  **  **  **        */ 
+ /*     ***  **  **  ***       */ 
+ /*     **   **  **   **       */ 
+ /*     **   **  **   **       */ 
+ /*     **   **  **   **       */ 
+ /*     **       **   **       */ 
+ /*     **            **       */ 
+ /*     **            **       */ 
+  0x01, 0x7f, 0x22, 0x2d, 0x68, 0xd3, 0xcd, 0x06, 
+  0x26, 0xc2, 0x22, 0x22, 0x22, 0xb3, 0x22, 0x22, 
+  0x23, 0xae, 0x12, 0x32, 0x22, 0x32, 0xa2, 0x72, 
+  0x32, 0xa2, 0xc2, 0xa2, 0xc2, 0x61, 
+
+};
+
+/* Character descriptors */
+const FONT_CHAR_INFO Ubuntu18ptLengths[] = {
+ { 2}, /*   */
+ { 5}, /* ! */
+ { 7}, /* " */
+ {38}, /* # */
+ {26}, /* $ */
+ {45}, /* % */
+ {37}, /* & */
+ { 4}, /* ' */
+ {13}, /* ( */
+ {12}, /* ) */
+ {20}, /* * */
+ { 9}, /* + */
+ { 6}, /* , */
+ { 5}, /* - */
+ { 5}, /* . */
+ {15}, /* / */
+ {20}, /* 0 */
+ {10}, /* 1 */
+ {30}, /* 2 */
+ {25}, /* 3 */
+ {24}, /* 4 */
+ {24}, /* 5 */
+ {29}, /* 6 */
+ {21}, /* 7 */
+ {33}, /* 8 */
+ {29}, /* 9 */
+ { 6}, /* : */
+ { 8}, /* ; */
+ {23}, /* < */
+ { 6}, /* = */
+ {23}, /* > */
+ {19}, /* ? */
+ {46}, /* @ */
+ {29}, /* A */
+ {21}, /* B */
+ {21}, /* C */
+ {18}, /* D */
+ {10}, /* E */
+ {10}, /* F */
+ {21}, /* G */
+ {10}, /* H */
+ { 5}, /* I */
+ {13}, /* J */
+ {28}, /* K */
+ { 7}, /* L */
+ {28}, /* M */
+ {22}, /* N */
+ {28}, /* O */
+ {19}, /* P */
+ {40}, /* Q */
+ {22}, /* R */
+ {31}, /* S */
+ { 9}, /* T */
+ {18}, /* U */
+ {25}, /* V */
+ {34}, /* W */
+ {33}, /* X */
+ {21}, /* Y */
+ {33}, /* Z */
+ { 8}, /* [ */
+ {16}, /* \ */
+ { 7}, /* ] */
+ {19}, /* ^ */
+ { 5}, /* _ */
+ {10}, /* ` */
+ {21}, /* a */
+ {18}, /* b */
+ {14}, /* c */
+ {19}, /* d */
+ {28}, /* e */
+ {13}, /* f */
+ {21}, /* g */
+ {12}, /* h */
+ { 6}, /* i */
+ {10}, /* j */
+ {23}, /* k */
+ { 8}, /* l */
+ {19}, /* m */
+ {12}, /* n */
+ {22}, /* o */
+ {19}, /* p */
+ {18}, /* q */
+ { 8}, /* r */
+ {29}, /* s */
+ {11}, /* t */
+ {13}, /* u */
+ {18}, /* v */
+ {29}, /* w */
+ {28}, /* x */
+ {21}, /* y */
+ {28}, /* z */
+ {15}, /* { */
+ { 5}, /* | */
+ {14}, /* } */
+ {17}, /* ~ */
+ {32}, /* Ä */
+ {39}, /* Ö */
+ {26}, /* Ü */
+ {31}, /* ß */
+ {30}, /* ä */
+ {29}, /* ö */
+ {19}, /* ü */
+ {30}, /* € */
+};
+
+const uint16_t Ubuntu18ptExtra[] = {
+196,214,220,223,228,246,252,8364,65535
+};
+
+/* Font info */
+const struct FONT_DEF Font_Ubuntu18pt = {
+         1,   /* width (1 == comressed) */
+        26,   /* character height */
+        32,   /* first char */
+       126,   /* last char */
+    Ubuntu18ptBitmaps, Ubuntu18ptLengths, Ubuntu18ptExtra
+};
+
+/* Font metadata: 
+ * Name:          Ubuntu Regular 18pt
+ * Height:        26 px (4 bytes)
+ * Maximum width: 23 px
+ * Storage size:  2104 bytes (compressed by 62%)
+ */
diff --git a/lcd/fonts/ubuntu18.h b/lcd/fonts/ubuntu18.h
new file mode 100644 (file)
index 0000000..aac41ad
--- /dev/null
@@ -0,0 +1,3 @@
+#include "lcd/fonts.h"
+
+extern const struct FONT_DEF Font_Ubuntu18pt;
diff --git a/lcd/fonts/ubuntu29.c b/lcd/fonts/ubuntu29.c
new file mode 100644 (file)
index 0000000..ebf15ea
--- /dev/null
@@ -0,0 +1,2604 @@
+#include "ubuntu29.h"
+
+/* Font data for Ubuntu Regular 29pt */
+
+/* Copyright 2010 Canonical Ltd.  Licensed under the Ubuntu Font Licence 1.0
+ * 
+ */
+
+/* This file created by makefont.pl by Sec <sec@42.org> */
+
+/* Bitmaps */
+const uint8_t Ubuntu29ptBitmaps[] = {
+ /* Char 32 is 10px wide @ 0 */
+ /*                                            */ 
+  0x00, 0x19, 0x81, 
+
+ /* Char 33 is 11px wide @ 3 */
+ /*         ***                                */ 
+ /*        *****      ****************         */ 
+ /*        *****    ******************         */ 
+ /*        *****    ******************         */ 
+ /*        *****      ****************         */ 
+ /*         ***                                */ 
+  0x07, 0xa3, 0x01, 0xa5, 0x6d, 0x3d, 0x2f, 0x54, 
+  0xd5, 0xd2, 0x56, 0xd3, 0xd3, 0x30, 0x67, 
+
+ /* Char 34 is 17px wide @ 18 */
+ /*                               ********     */ 
+ /*                             **********     */ 
+ /*                             **********     */ 
+ /*                               ********     */ 
+ /*                                            */ 
+ /*                                            */ 
+ /*                                            */ 
+ /*                               ********     */ 
+ /*                             **********     */ 
+ /*                             **********     */ 
+ /*                               ********     */ 
+  0x09, 0x08, 0x01, 0x4f, 0xa0, 0x16, 0x80, 0x94, 
+  0x80, 0x14, 0xfa, 0x01, 0x68, 0x07, 0x61, 
+
+ /* Char 35 is 27px wide @ 33 */
+ /*               ***       ***                */ 
+ /*               ***       ***                */ 
+ /*        ***    ***       ***                */ 
+ /*        **********       ***                */ 
+ /*        **************   ***                */ 
+ /*        ********************                */ 
+ /*          ***********************           */ 
+ /*               ********************         */ 
+ /*               ***   **************         */ 
+ /*               ***       **********         */ 
+ /*               ***       ***    ***         */ 
+ /*        ***    ***       ***                */ 
+ /*        **********       ***                */ 
+ /*        **************   ***                */ 
+ /*        ********************                */ 
+ /*          ***********************           */ 
+ /*               ********************         */ 
+ /*               ***   **************         */ 
+ /*               ***       **********         */ 
+ /*               ***       ***    ***         */ 
+ /*               ***       ***                */ 
+ /*               ***       ***                */ 
+  0x05, 0x6f, 0x37, 0x3d, 0x93, 0x43, 0x73, 0xd9, 
+  0xa7, 0x3d, 0x9d, 0x13, 0x3d, 0x9d, 0x7d, 0xbd, 
+  0xad, 0xbd, 0x7d, 0x93, 0x3d, 0x1d, 0x93, 0x7a, 
+  0xd9, 0x37, 0x34, 0x3d, 0x23, 0x43, 0x73, 0xd9, 
+  0xa7, 0x3d, 0x9d, 0x13, 0x3d, 0x9d, 0x7d, 0xbd, 
+  0xad, 0xbd, 0x7d, 0x93, 0x3d, 0x1d, 0x93, 0x7a, 
+  0xd9, 0x37, 0x34, 0x3d, 0x9f, 0x37, 0x30, 0x81, 
+
+
+ /* Char 36 is 23px wide @ 89 */
+ /*         **                                 */ 
+ /*         ***            ******              */ 
+ /*         ***           ********             */ 
+ /*        ****          **********            */ 
+ /*        ***          ************           */ 
+ /*        ***         ******   ****           */ 
+ /*        ***         ****      ****          */ 
+ /*   ********        *****       *******      */ 
+ /*   ********        ****        *******      */ 
+ /*   ********        ****        *******      */ 
+ /*        ***       ****         ***          */ 
+ /*        ****      ****         ***          */ 
+ /*         ****   ******         ***          */ 
+ /*         ************         ****          */ 
+ /*          **********          ***           */ 
+ /*           ********            **           */ 
+ /*            ******                          */ 
+  0x05, 0x02, 0x01, 0xc3, 0xc6, 0xd8, 0x3b, 0x8d, 
+  0x64, 0xaa, 0xd5, 0x3a, 0xcd, 0x43, 0x96, 0x34, 
+  0xd4, 0x39, 0x46, 0x4b, 0x88, 0x57, 0x77, 0xf8, 
+  0x84, 0x87, 0xc3, 0x74, 0x93, 0xd3, 0x46, 0x49, 
+  0x3d, 0x44, 0x36, 0x93, 0xd4, 0xc9, 0x4d, 0x5a, 
+  0xa3, 0xd7, 0x8c, 0x2d, 0x86, 0x0b, 0x51, 
+
+ /* Char 37 is 34px wide @ 136 */
+ /*                        *******             */ 
+ /*                      ***********           */ 
+ /*                     *************          */ 
+ /*                     *****   *****          */ 
+ /*                    ****       ****         */ 
+ /*        *           ***         ***         */ 
+ /*        ***         ***         ***         */ 
+ /*        ****        ****       ****         */ 
+ /*        ******       *****   *****          */ 
+ /*          ******     *************          */ 
+ /*            ******    ***********           */ 
+ /*             ******     *******             */ 
+ /*               ******                       */ 
+ /*                 ******                     */ 
+ /*                   *****                    */ 
+ /*                    ******                  */ 
+ /*                      ******                */ 
+ /*            *******     ******              */ 
+ /*          ***********    ******             */ 
+ /*         *************     ******           */ 
+ /*         *****   *****       ******         */ 
+ /*        ****       ****        ****         */ 
+ /*        ***         ***         ***         */ 
+ /*        ***         ***           *         */ 
+ /*        ****       ****                     */ 
+ /*         *****   *****                      */ 
+ /*         *************                      */ 
+ /*          ***********                       */ 
+ /*            *******                         */ 
+  0x05, 0xf7, 0x01, 0x5b, 0x01, 0x2d, 0x00, 0x11, 
+  0x53, 0x5d, 0xf4, 0x74, 0xd2, 0x1b, 0x39, 0x3d, 
+  0x23, 0x93, 0x93, 0xd2, 0x48, 0x47, 0x4d, 0x26, 
+  0x75, 0x35, 0xd5, 0x65, 0xd0, 0xd7, 0x64, 0xbd, 
+  0x96, 0x57, 0xdd, 0x60, 0x1a, 0x60, 0x1a, 0x50, 
+  0x1a, 0x60, 0x1a, 0x6d, 0xd7, 0x56, 0xd9, 0xb4, 
+  0x6d, 0x7d, 0x05, 0x6d, 0x55, 0x35, 0x76, 0xd2, 
+  0x47, 0x48, 0x4d, 0x23, 0x93, 0x93, 0xd2, 0x39, 
+  0x3b, 0x1d, 0x24, 0x74, 0xdf, 0x53, 0x50, 0x11, 
+  0xd0, 0x01, 0x2b, 0x01, 0x57, 0x08, 0xa1, 
+
+ /* Char 38 is 27px wide @ 215 */
+ /*             *****                          */ 
+ /*           ********                         */ 
+ /*          **********                        */ 
+ /*         ************     *****             */ 
+ /*         ****    *****  *********           */ 
+ /*        ****       ***************          */ 
+ /*        ****        **************          */ 
+ /*        ***         *******    ****         */ 
+ /*        ***        ******      ****         */ 
+ /*        ***       *******       ***         */ 
+ /*        ***      ********       ***         */ 
+ /*        ***     ***********    ****         */ 
+ /*         ***   *****   ***********          */ 
+ /*         ***  *****     **********          */ 
+ /*         *********       ********           */ 
+ /*          *******          *****            */ 
+ /*          ******                            */ 
+ /*         ********                           */ 
+ /*        ***********                         */ 
+ /*        *****  ******                       */ 
+ /*        ****    *****                       */ 
+ /*        ***        **                       */ 
+ /*        *                                   */ 
+  0x05, 0x45, 0x01, 0x78, 0x01, 0x5a, 0x01, 0x3c, 
+  0x55, 0xd7, 0x44, 0x52, 0x9d, 0x44, 0x7d, 0x2d, 
+  0x34, 0x8d, 0x1d, 0x33, 0x97, 0x44, 0xd2, 0x38, 
+  0x66, 0x4d, 0x23, 0x77, 0x73, 0xd2, 0x36, 0x87, 
+  0x3d, 0x23, 0x5b, 0x44, 0xd3, 0x33, 0x53, 0xbd, 
+  0x43, 0x25, 0x5a, 0xd4, 0x97, 0x8d, 0x67, 0xa5, 
+  0xd7, 0x60, 0x17, 0x80, 0x15, 0xb0, 0x13, 0x52, 
+  0x60, 0x11, 0x44, 0x50, 0x11, 0x38, 0x20, 0x11, 
+  0x10, 0x6a, 
+
+ /* Char 39 is 10px wide @ 281 */
+ /*                               ********     */ 
+ /*                             **********     */ 
+ /*                             **********     */ 
+ /*                               ********     */ 
+  0x09, 0x08, 0x01, 0x4f, 0xa0, 0x16, 0x80, 0x76, 
+
+
+ /* Char 40 is 13px wide @ 289 */
+ /*              ************                  */ 
+ /*           ******************               */ 
+ /*        ************************            */ 
+ /*      ****************************          */ 
+ /*    ***********          ***********        */ 
+ /*   ********                  ********       */ 
+ /*  *******                      *******      */ 
+ /* ******                          ******     */ 
+ /*  ***                              ***      */ 
+ /*  **                                **      */ 
+  0x07, 0xfc, 0xde, 0xd5, 0xd8, 0xdb, 0xd3, 0xdf, 
+  0xcb, 0xab, 0x98, 0xd5, 0x87, 0x7d, 0x97, 0x56, 
+  0xdd, 0x65, 0x30, 0x12, 0x36, 0x20, 0x14, 0x25, 
+
+
+ /* Char 41 is 13px wide @ 313 */
+ /*  **                                **      */ 
+ /*  ***                              ***      */ 
+ /* ******                          ******     */ 
+ /*  *******                      *******      */ 
+ /*   ********                  ********       */ 
+ /*    ***********          ***********        */ 
+ /*      ****************************          */ 
+ /*        ************************            */ 
+ /*           ******************               */ 
+ /*              ************                  */ 
+  0x12, 0x01, 0x42, 0x63, 0x01, 0x23, 0x56, 0xdd, 
+  0x65, 0x7d, 0x97, 0x78, 0xd5, 0x89, 0xba, 0xbc, 
+  0xdf, 0xd3, 0xdb, 0xd8, 0xd5, 0xde, 0xc0, 0x83, 
+
+
+ /* Char 42 is 19px wide @ 337 */
+ /*                            **              */ 
+ /*                            ***             */ 
+ /*                      *    ***              */ 
+ /*                     ***   ***              */ 
+ /*                    *****  **               */ 
+ /*                     ***** **               */ 
+ /*                       ************         */ 
+ /*                         **********         */ 
+ /*                        ***********         */ 
+ /*                      **** **               */ 
+ /*                     ****  **               */ 
+ /*                    *****  ***              */ 
+ /*                     ***   ***              */ 
+ /*                      *     ***             */ 
+ /*                            **              */ 
+  0x06, 0x32, 0x01, 0xc3, 0x01, 0x51, 0x43, 0x01, 
+  0x53, 0x33, 0x01, 0x45, 0x22, 0x01, 0x65, 0x12, 
+  0x01, 0x8c, 0x01, 0x4a, 0x01, 0x3b, 0x01, 0x14, 
+  0x12, 0x01, 0x64, 0x22, 0x01, 0x55, 0x23, 0x01, 
+  0x53, 0x33, 0x01, 0x61, 0x53, 0x01, 0xb2, 0x05, 
+  0x51, 
+
+ /* Char 43 is 23px wide @ 378 */
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*          *******************               */ 
+ /*          *******************               */ 
+ /*          *******************               */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+  0x02, 0xfe, 0x63, 0x01, 0x3e, 0x1d, 0x60, 0x13, 
+  0xe6, 0x30, 0x88, 
+
+ /* Char 44 is 10px wide @ 389 */
+ /*   *                                        */ 
+ /*  *****                                     */ 
+ /*  **********                                */ 
+ /*  **********                                */ 
+ /*    ********                                */ 
+ /*       *****                                */ 
+  0x02, 0x01, 0x01, 0xc5, 0x01, 0x9f, 0xa0, 0x16, 
+  0x80, 0x19, 0x50, 0x91, 
+
+ /* Char 45 is 12px wide @ 401 */
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+ /*                  ***                       */ 
+  0x02, 0xfe, 0x83, 0x03, 0x41, 
+
+ /* Char 46 is 10px wide @ 406 */
+ /*         ***                                */ 
+ /*        *****                               */ 
+ /*        *****                               */ 
+ /*        *****                               */ 
+ /*         ***                                */ 
+  0x05, 0x03, 0x01, 0xae, 0x15, 0x01, 0xa3, 0x09, 
+  0x11, 
+
+ /* Char 47 is 15px wide @ 415 */
+ /* ****                                       */ 
+ /* *******                                    */ 
+ /*  *********                                 */ 
+ /*     *********                              */ 
+ /*       *********                            */ 
+ /*          *********                         */ 
+ /*             *********                      */ 
+ /*                ********                    */ 
+ /*                  *********                 */ 
+ /*                     *********              */ 
+ /*                        *********           */ 
+ /*                          *********         */ 
+ /*                             *********      */ 
+ /*                                *******     */ 
+ /*                                   ****     */ 
+  0xe4, 0x01, 0xa7, 0x01, 0x89, 0x01, 0x89, 0x01, 
+  0x79, 0x01, 0x89, 0x01, 0x89, 0x01, 0x88, 0x01, 
+  0x89, 0x01, 0x89, 0x01, 0x89, 0x01, 0x79, 0x01, 
+  0x89, 0x01, 0x87, 0x01, 0xa4, 0x41, 
+
+ /* Char 48 is 23px wide @ 445 */
+ /*                ***********                 */ 
+ /*             *****************              */ 
+ /*           *********************            */ 
+ /*          ***********************           */ 
+ /*         ********         ********          */ 
+ /*         *****               *****          */ 
+ /*         ***                   ***          */ 
+ /*        ****                   ****         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ****                   ****         */ 
+ /*         ***                   ***          */ 
+ /*         *****               *****          */ 
+ /*         ********         ********          */ 
+ /*          ***********************           */ 
+ /*           *********************            */ 
+ /*             *****************              */ 
+ /*                ***********                 */ 
+  0x05, 0x7b, 0xdf, 0xd4, 0xda, 0xd8, 0xd7, 0xda, 
+  0xd5, 0x89, 0x8d, 0x45, 0xd2, 0x5d, 0x43, 0xd6, 
+  0x3d, 0x34, 0xd6, 0x4d, 0x2f, 0x3d, 0x83, 0xd2, 
+  0x4d, 0x64, 0xd3, 0x3d, 0x63, 0xd4, 0x5d, 0x25, 
+  0xd4, 0x89, 0x8d, 0x5d, 0xad, 0x7d, 0x8d, 0xad, 
+  0x4d, 0xfb, 0x08, 0x21, 
+
+ /* Char 49 is 23px wide @ 489 */
+ /*                            **              */ 
+ /*                           ****             */ 
+ /*                            ***             */ 
+ /*                            ****            */ 
+ /*                            ****            */ 
+ /*                             ****           */ 
+ /*                              ****          */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+  0x0b, 0x72, 0x01, 0xb4, 0x01, 0xb3, 0x01, 0xbf, 
+  0x40, 0x1b, 0x40, 0x1b, 0x4d, 0x3e, 0x2d, 0xe0, 
+  0x01, 0x4c, 
+
+ /* Char 50 is 23px wide @ 507 */
+ /*                               *            */ 
+ /*        *****                 ***           */ 
+ /*        *******               ****          */ 
+ /*        *********              ***          */ 
+ /*        **********             ****         */ 
+ /*        ***  ******             ***         */ 
+ /*        ***   ******            ***         */ 
+ /*        ***     *****           ***         */ 
+ /*        ***      ****           ***         */ 
+ /*        ***      ******         ***         */ 
+ /*        ***       ******       ****         */ 
+ /*        ***        *******    ****          */ 
+ /*        ***         **************          */ 
+ /*        ***          ************           */ 
+ /*        ***            *********            */ 
+ /*        ***              ******             */ 
+ /*        ***                                 */ 
+  0x06, 0x61, 0xd5, 0x5d, 0x43, 0xd4, 0x7d, 0x24, 
+  0xd3, 0x9d, 0x13, 0xd3, 0xad, 0x04, 0xd2, 0x32, 
+  0x6d, 0x03, 0xd2, 0x33, 0x6c, 0x3d, 0x23, 0x55, 
+  0xb3, 0xd2, 0x36, 0x4b, 0x3d, 0x23, 0x66, 0x93, 
+  0xd2, 0x37, 0x67, 0x4d, 0x23, 0x87, 0x44, 0xd3, 
+  0x39, 0xd1, 0xd3, 0x3a, 0xcd, 0x43, 0xc9, 0xd5, 
+  0x3d, 0x16, 0xd6, 0x30, 0xbc, 
+
+ /* Char 51 is 23px wide @ 560 */
+ /*         ***                                */ 
+ /*         ***                    *           */ 
+ /*         ***                   ***          */ 
+ /*        ***                    ***          */ 
+ /*        ***                    ****         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***         *****       ***         */ 
+ /*        ****        *****      ****         */ 
+ /*         ***       ********   *****         */ 
+ /*         *****    ****************          */ 
+ /*          ************  *********           */ 
+ /*          ************   ********           */ 
+ /*            *********     *****             */ 
+ /*             ******                         */ 
+  0x05, 0x03, 0x01, 0xb3, 0xd7, 0x1d, 0x53, 0xd6, 
+  0x3d, 0x33, 0xd7, 0x3d, 0x33, 0xd7, 0x4d, 0x2e, 
+  0x23, 0xa3, 0x83, 0xd2, 0x39, 0x57, 0x3d, 0x24, 
+  0x85, 0x64, 0xd3, 0x37, 0x83, 0x5d, 0x35, 0x4d, 
+  0x3d, 0x5c, 0x29, 0xd6, 0xc3, 0x8d, 0x89, 0x55, 
+  0xdb, 0x60, 0xb4, 
+
+ /* Char 52 is 23px wide @ 603 */
+ /*               ****                         */ 
+ /*               ******                       */ 
+ /*               ********                     */ 
+ /*               **********                   */ 
+ /*               *** *******                  */ 
+ /*               ***   *******                */ 
+ /*               ***     ******               */ 
+ /*               ***       ******             */ 
+ /*               ***        ******            */ 
+ /*               ***          *****           */ 
+ /*               ***           *****          */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*               ***                          */ 
+ /*               ***                          */ 
+ /*               ***                          */ 
+  0x05, 0x64, 0x01, 0xa6, 0x01, 0x88, 0x01, 0x6a, 
+  0x01, 0x43, 0x17, 0x01, 0x33, 0x37, 0x01, 0x13, 
+  0x56, 0xdf, 0x37, 0x6d, 0xd3, 0x86, 0xdc, 0x3a, 
+  0x5d, 0xb3, 0xb5, 0xd3, 0xe2, 0xde, 0xd9, 0xe1, 
+  0x30, 0x8b, 
+
+ /* Char 53 is 23px wide @ 637 */
+ /*         ***                                */ 
+ /*         ***                                */ 
+ /*        ****          ******                */ 
+ /*        ***           *************         */ 
+ /*        ***           *************         */ 
+ /*        ***           *************         */ 
+ /*        ***           ***   *******         */ 
+ /*        ***          ****       ***         */ 
+ /*        ***          ****       ***         */ 
+ /*        ****        ****        ***         */ 
+ /*         ***        ****        ***         */ 
+ /*         *****    ******        ***         */ 
+ /*          *************         ***         */ 
+ /*          *************         ***         */ 
+ /*           **********           ***         */ 
+ /*             ******                         */ 
+  0x07, 0xaf, 0x30, 0x1a, 0x4a, 0x6d, 0x9e, 0x13, 
+  0xbd, 0x0d, 0x23, 0xb3, 0x37, 0xd2, 0xf3, 0xa4, 
+  0x73, 0xd2, 0x48, 0x48, 0x3d, 0x33, 0x84, 0x83, 
+  0xd3, 0x54, 0x68, 0x3d, 0x4f, 0xd0, 0x93, 0xd5, 
+  0xab, 0x3d, 0x76, 0x0b, 0x41, 
+
+ /* Char 54 is 23px wide @ 674 */
+ /*               *********                    */ 
+ /*             **************                 */ 
+ /*           *****************                */ 
+ /*          ********************              */ 
+ /*         ******      **********             */ 
+ /*         ****        ***  ******            */ 
+ /*        ****          ***   ****            */ 
+ /*        ****          ***    ****           */ 
+ /*        ***           ***     ****          */ 
+ /*        ***           ***     ****          */ 
+ /*        ***           ***      ***          */ 
+ /*        ****         ****      ****         */ 
+ /*         ****        ****       ***         */ 
+ /*         *****     *****        ***         */ 
+ /*          **************        ***         */ 
+ /*           ************         ***         */ 
+ /*            **********                      */ 
+ /*              ******                        */ 
+  0x05, 0x69, 0x01, 0x3d, 0x1d, 0xdd, 0x4d, 0xbd, 
+  0x7d, 0x86, 0x6a, 0xd7, 0x48, 0x32, 0x6d, 0x54, 
+  0xa3, 0x34, 0xd5, 0x4a, 0x34, 0x4d, 0x4f, 0x3b, 
+  0x35, 0x4d, 0x33, 0xb3, 0x63, 0xd3, 0x49, 0x46, 
+  0x4d, 0x34, 0x84, 0x73, 0xd3, 0x55, 0x58, 0x3d, 
+  0x4d, 0x18, 0x3d, 0x5c, 0x93, 0xd6, 0xa0, 0x16, 
+  0x60, 0x89, 
+
+ /* Char 55 is 23px wide @ 724 */
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*        ***                     ***         */ 
+ /*        ********                ***         */ 
+ /*        **********              ***         */ 
+ /*        *************           ***         */ 
+ /*          *************         ***         */ 
+ /*                *********       ***         */ 
+ /*                  *********     ***         */ 
+ /*                     ********   ***         */ 
+ /*                       *******  ***         */ 
+ /*                         ****** ***         */ 
+ /*                           ********         */ 
+ /*                             ******         */ 
+ /*                              *****         */ 
+ /*                               ****         */ 
+  0x06, 0x7e, 0x23, 0xd2, 0x3d, 0x83, 0xd2, 0x8d, 
+  0x33, 0xd2, 0xad, 0x13, 0xd2, 0xd0, 0xb3, 0xd4, 
+  0xd0, 0x93, 0xda, 0x97, 0x3d, 0xc9, 0x53, 0xdf, 
+  0x83, 0x30, 0x12, 0x72, 0x30, 0x14, 0x61, 0x30, 
+  0x16, 0x80, 0x18, 0x60, 0x19, 0x50, 0x1a, 0x40, 
+  0x7a, 
+
+ /* Char 56 is 23px wide @ 765 */
+ /*            *****                           */ 
+ /*           ********       ****              */ 
+ /*          **********    ********            */ 
+ /*         ************  **********           */ 
+ /*         ****    **** ************          */ 
+ /*        ****       ********   ****          */ 
+ /*        ****       ******      ****         */ 
+ /*        ***         *****       ***         */ 
+ /*        ***         ****        ***         */ 
+ /*        ***        *****        ***         */ 
+ /*        ***       ******        ***         */ 
+ /*        ****      *******      ****         */ 
+ /*        ****     **********   ****          */ 
+ /*         ****   ***** ************          */ 
+ /*         ************  **********           */ 
+ /*          **********    ********            */ 
+ /*           ********      ******             */ 
+ /*            ******                          */ 
+  0x05, 0x35, 0x01, 0x88, 0x74, 0xd9, 0xa4, 0x8d, 
+  0x6c, 0x2a, 0xd5, 0x44, 0x41, 0xcd, 0x34, 0x78, 
+  0x34, 0xd3, 0x47, 0x66, 0x4d, 0x23, 0x95, 0x73, 
+  0xd2, 0x39, 0x48, 0x3d, 0x23, 0x85, 0x83, 0xd2, 
+  0x37, 0x68, 0x3d, 0x24, 0x67, 0x64, 0xd2, 0x45, 
+  0xa3, 0x4d, 0x44, 0x35, 0x1c, 0xd4, 0xc2, 0xad, 
+  0x6a, 0x48, 0xd8, 0x86, 0x6d, 0xa6, 0x08, 0xb1, 
+
+
+ /* Char 57 is 23px wide @ 821 */
+ /*                       ******               */ 
+ /*                     **********             */ 
+ /*        ***         ************            */ 
+ /*        ***        **************           */ 
+ /*        ***        *****     *****          */ 
+ /*        ***       ****        ****          */ 
+ /*         ***      ****         ****         */ 
+ /*         ***      ***           ***         */ 
+ /*         ***      ***           ***         */ 
+ /*         ****     ***           ***         */ 
+ /*          ****    ***          ****         */ 
+ /*          *****   ***          ****         */ 
+ /*           *****   ***        ****          */ 
+ /*            **********     *******          */ 
+ /*             ********************           */ 
+ /*              ******************            */ 
+ /*                **************              */ 
+ /*                    ********                */ 
+  0x05, 0xe6, 0x01, 0x6a, 0xd6, 0x39, 0xcd, 0x53, 
+  0x8d, 0x1d, 0x43, 0x85, 0x55, 0xd3, 0x37, 0x48, 
+  0x4d, 0x43, 0x64, 0x94, 0xd3, 0xf3, 0x63, 0xb3, 
+  0xd3, 0x45, 0x3b, 0x3d, 0x44, 0x43, 0xa4, 0xd4, 
+  0x53, 0x3a, 0x4d, 0x55, 0x33, 0x84, 0xd7, 0xa5, 
+  0x7d, 0x8d, 0x7d, 0xad, 0x5d, 0xdd, 0x10, 0x14, 
+  0x80, 0x81, 
+
+ /* Char 58 is 10px wide @ 871 */
+ /*         ***             ***                */ 
+ /*        *****           *****               */ 
+ /*        *****           *****               */ 
+ /*        *****           *****               */ 
+ /*         ***             ***                */ 
+  0x05, 0x03, 0xd0, 0x3d, 0x9e, 0x15, 0xb5, 0xd9, 
+  0x3d, 0x03, 0x08, 0x11, 
+
+ /* Char 59 is 10px wide @ 883 */
+ /*   *                                        */ 
+ /*  *****                  ***                */ 
+ /*  **********            *****               */ 
+ /*  **********            *****               */ 
+ /*    ********            *****               */ 
+ /*       *****             ***                */ 
+  0x02, 0x01, 0x01, 0xc5, 0xd5, 0x3d, 0x3f, 0xac, 
+  0x5d, 0x48, 0xc5, 0xd7, 0x5d, 0x03, 0x08, 0x11, 
+
+
+ /* Char 60 is 23px wide @ 899 */
+ /*                  ***                       */ 
+ /*                 *****                      */ 
+ /*                 *****                      */ 
+ /*                *******                     */ 
+ /*                *******                     */ 
+ /*                *** ***                     */ 
+ /*               **** ****                    */ 
+ /*               ***   ***                    */ 
+ /*              ****   ****                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*             ****     ****                  */ 
+ /*             ***       ***                  */ 
+ /*            ****       ****                 */ 
+ /*            ***         ***                 */ 
+ /*            ***         ***                 */ 
+ /*           ***           ***                */ 
+ /*            **           **                 */ 
+  0x05, 0x93, 0x01, 0xaf, 0x50, 0x18, 0xf7, 0x01, 
+  0x73, 0x13, 0x01, 0x64, 0x14, 0x01, 0x53, 0x33, 
+  0x01, 0x44, 0x34, 0x01, 0x3f, 0x35, 0x30, 0x12, 
+  0x45, 0x40, 0x11, 0x37, 0x3d, 0xf4, 0x74, 0xde, 
+  0xf3, 0x93, 0xdd, 0x3b, 0x3d, 0xd2, 0xb2, 0x08, 
+  0x21, 
+
+ /* Char 61 is 23px wide @ 940 */
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+  0x05, 0x5e, 0x01, 0x03, 0x53, 0x08, 0x41, 
+
+ /* Char 62 is 23px wide @ 947 */
+ /*            **           **                 */ 
+ /*           ***           ***                */ 
+ /*            ***         ***                 */ 
+ /*            ***         ***                 */ 
+ /*            ****       ****                 */ 
+ /*             ***       ***                  */ 
+ /*             ****     ****                  */ 
+ /*              ***     ***                   */ 
+ /*              ***     ***                   */ 
+ /*              ****   ****                   */ 
+ /*               ***   ***                    */ 
+ /*               **** ****                    */ 
+ /*                *** ***                     */ 
+ /*                *******                     */ 
+ /*                *******                     */ 
+ /*                 *****                      */ 
+ /*                 *****                      */ 
+ /*                  ***                       */ 
+  0x05, 0x32, 0xb2, 0xdd, 0x3b, 0x3d, 0xdf, 0x39, 
+  0x3d, 0xe4, 0x74, 0xdf, 0x37, 0x30, 0x11, 0x45, 
+  0x40, 0x12, 0xf3, 0x53, 0x01, 0x34, 0x34, 0x01, 
+  0x43, 0x33, 0x01, 0x54, 0x14, 0x01, 0x63, 0x13, 
+  0x01, 0x7f, 0x70, 0x18, 0xf5, 0x01, 0xa3, 0x08, 
+  0x81, 
+
+ /* Char 63 is 16px wide @ 988 */
+ /*                                **          */ 
+ /*                               ***          */ 
+ /*                               ***          */ 
+ /*                                ***         */ 
+ /*         ***     ****           ***         */ 
+ /*        *****    *****          ***         */ 
+ /*        *****    ******         ***         */ 
+ /*         ***     *******       ****         */ 
+ /*                    *****      ****         */ 
+ /*                      *****   *****         */ 
+ /*                       ***********          */ 
+ /*                        **********          */ 
+ /*                         ********           */ 
+ /*                           ****             */ 
+  0x03, 0xd2, 0x01, 0xbf, 0x30, 0x1c, 0x3d, 0x33, 
+  0x54, 0xb3, 0xd2, 0x54, 0x5a, 0x3d, 0x25, 0x46, 
+  0x93, 0xd3, 0x35, 0x77, 0x4d, 0xe5, 0x64, 0x01, 
+  0x15, 0x35, 0x01, 0x2b, 0x01, 0x4a, 0x01, 0x58, 
+  0x01, 0x84, 0x02, 0xa1, 
+
+ /* Char 64 is 38px wide @ 1024 */
+ /*              **********                    */ 
+ /*           ****************                 */ 
+ /*         ********************               */ 
+ /*        **********************              */ 
+ /*      **********      *********             */ 
+ /*     *******              ******            */ 
+ /*     *****                  *****           */ 
+ /*    *****                    *****          */ 
+ /*    ****       *******        ****          */ 
+ /*   ****      ***********       ****         */ 
+ /*   ****     **************     ****         */ 
+ /*   ***     ***************      ***         */ 
+ /*   ***     *****      *****     ****        */ 
+ /*  ****    ****          ****    ****        */ 
+ /*  ***     ***            ***     ***        */ 
+ /*  ***     ***            ***     ***        */ 
+ /*  ***     ***            ***     ***        */ 
+ /*  ***     ***            ***     ***        */ 
+ /*  ***      *****************     ***        */ 
+ /*  ***      *****************    ****        */ 
+ /*  ***      *****************    ****        */ 
+ /*   **     *****************     ***         */ 
+ /*          ****                 ****         */ 
+ /*          ***                 ****          */ 
+ /*          ***                 ****          */ 
+ /*          ****              *****           */ 
+ /*          *****            ******           */ 
+ /*           ******      *********            */ 
+ /*            ******************              */ 
+ /*             ****************               */ 
+ /*              **************                */ 
+ /*                 ********                   */ 
+  0x05, 0x5a, 0x01, 0x1d, 0x3d, 0xbd, 0x7d, 0x8d, 
+  0x9d, 0x5a, 0x69, 0xd3, 0x7d, 0x16, 0xd2, 0x5d, 
+  0x55, 0xd0, 0x5d, 0x75, 0xc4, 0x77, 0x84, 0xb4, 
+  0x6b, 0x74, 0xa4, 0x5d, 0x15, 0x4a, 0x35, 0xd2, 
+  0x63, 0xa3, 0x55, 0x65, 0x54, 0x84, 0x44, 0xa4, 
+  0x44, 0x8e, 0x23, 0x53, 0xc3, 0x53, 0x83, 0x6d, 
+  0x45, 0x38, 0xf3, 0x6d, 0x44, 0x49, 0x25, 0xd4, 
+  0x53, 0xd4, 0x4d, 0x44, 0xd4, 0xf3, 0xd4, 0x4d, 
+  0x54, 0xd1, 0x5d, 0x65, 0xc6, 0xd7, 0x66, 0x9d, 
+  0x9d, 0x5d, 0xcd, 0x3d, 0xed, 0x10, 0x13, 0x80, 
+  0xae, 
+
+ /* Char 65 is 26px wide @ 1105 */
+ /*        **                                  */ 
+ /*        ****                                */ 
+ /*        *******                             */ 
+ /*        **********                          */ 
+ /*         ************                       */ 
+ /*           *************                    */ 
+ /*              ************                  */ 
+ /*               **************               */ 
+ /*               ***  ************            */ 
+ /*               ***    *************         */ 
+ /*               ***       **********         */ 
+ /*               ***          *******         */ 
+ /*               ***            *****         */ 
+ /*               ***          *******         */ 
+ /*               ***        *********         */ 
+ /*               ***     ***********          */ 
+ /*               ***   ***********            */ 
+ /*               **************               */ 
+ /*               ************                 */ 
+ /*             ***********                    */ 
+ /*           ***********                      */ 
+ /*        ***********                         */ 
+ /*        *********                           */ 
+ /*        ******                              */ 
+ /*        ****                                */ 
+ /*        *                                   */ 
+  0x72, 0x01, 0xc4, 0x01, 0xa7, 0x01, 0x7a, 0x01, 
+  0x5c, 0x01, 0x4d, 0x00, 0x14, 0xc0, 0x13, 0xd1, 
+  0xdf, 0x32, 0xcd, 0xc3, 0x4d, 0x0d, 0x93, 0x7a, 
+  0xd9, 0x3a, 0x7d, 0x93, 0xc5, 0xd9, 0x3a, 0x7d, 
+  0x93, 0x89, 0xd9, 0x35, 0xbd, 0xa3, 0x3b, 0xdc, 
+  0xd1, 0xdf, 0xcd, 0xfb, 0x01, 0x1b, 0xdf, 0xb0, 
+  0x13, 0x90, 0x15, 0x60, 0x18, 0x40, 0x1a, 0x10, 
+  0x16, 
+
+ /* Char 66 is 26px wide @ 1162 */
+ /*         *************************          */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***       ****         */ 
+ /*        ****        *****      ****         */ 
+ /*         ***        *****      ***          */ 
+ /*         ****      *******   *****          */ 
+ /*         ******   ****************          */ 
+ /*          ************  *********           */ 
+ /*           **********   ********            */ 
+ /*            *********     ****              */ 
+ /*              *****                         */ 
+  0x07, 0xad, 0xcd, 0x3e, 0x1d, 0xed, 0x2e, 0x53, 
+  0xa3, 0x83, 0xd2, 0x3a, 0x37, 0x4d, 0x24, 0x85, 
+  0x64, 0xd3, 0x38, 0x56, 0x3d, 0x44, 0x67, 0x35, 
+  0xd4, 0x63, 0xd3, 0xd5, 0xc2, 0x9d, 0x7a, 0x38, 
+  0xd9, 0x95, 0x4d, 0xd5, 0x08, 0xa1, 
+
+ /* Char 67 is 25px wide @ 1200 */
+ /*                  ********                  */ 
+ /*               *************                */ 
+ /*             *****************              */ 
+ /*            *******************             */ 
+ /*           *******      ********            */ 
+ /*          ******           ******           */ 
+ /*          ****               ****           */ 
+ /*         ****                 ****          */ 
+ /*         ***                   ***          */ 
+ /*        ****                   ***          */ 
+ /*        ****                   ****         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                    ****         */ 
+ /*        ****                   ****         */ 
+ /*         ***                   ***          */ 
+ /*         ***                  ****          */ 
+ /*         **                     *           */ 
+  0x05, 0x98, 0x01, 0x3d, 0x0d, 0xed, 0x4d, 0xbd, 
+  0x6d, 0x97, 0x68, 0xd7, 0x6b, 0x6d, 0x64, 0xd2, 
+  0x4d, 0x54, 0xd4, 0x4d, 0x43, 0xd6, 0x3d, 0x34, 
+  0xd6, 0x3d, 0x34, 0xd6, 0x4d, 0x2e, 0x33, 0xd8, 
+  0x3d, 0x23, 0xd7, 0x4d, 0x24, 0xd6, 0x4d, 0x33, 
+  0xd6, 0x3d, 0x43, 0xd5, 0x4d, 0x42, 0xd8, 0x10, 
+  0x52, 
+
+ /* Char 68 is 28px wide @ 1249 */
+ /*         *************************          */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ****                   ****         */ 
+ /*         ***                   ***          */ 
+ /*         ***                   ***          */ 
+ /*         ****                 ****          */ 
+ /*          ***                 ***           */ 
+ /*          ****               ****           */ 
+ /*           *****           *****            */ 
+ /*           ********     ********            */ 
+ /*            *******************             */ 
+ /*              ***************               */ 
+ /*               *************                */ 
+ /*                 *********                  */ 
+  0x07, 0xad, 0xcd, 0x3e, 0x1d, 0xed, 0x2e, 0x53, 
+  0xd8, 0x3d, 0x24, 0xd6, 0x4d, 0x3f, 0x3d, 0x63, 
+  0xd4, 0x4d, 0x44, 0xd5, 0x3d, 0x43, 0xd6, 0x4d, 
+  0x24, 0xd7, 0x5b, 0x5d, 0x88, 0x58, 0xd9, 0xd6, 
+  0xdc, 0xd2, 0xdf, 0xd0, 0x01, 0x39, 0x05, 0x91, 
+
+
+ /* Char 69 is 23px wide @ 1289 */
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***          ***        ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                                 */ 
+  0x07, 0x9e, 0x2d, 0xed, 0x2e, 0xa3, 0xa3, 0x83, 
+  0xd2, 0x3d, 0x83, 0xd2, 0x30, 0x68, 
+
+ /* Char 70 is 22px wide @ 1303 */
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                    ***         ***         */ 
+ /*                                ***         */ 
+  0x07, 0x9e, 0x2d, 0xed, 0xee, 0xa3, 0x93, 0x01, 
+  0xb3, 0x05, 0x01, 
+
+ /* Char 71 is 27px wide @ 1314 */
+ /*                  ********                  */ 
+ /*               *************                */ 
+ /*             *****************              */ 
+ /*           ********************             */ 
+ /*           *******      ********            */ 
+ /*          *****            ******           */ 
+ /*         *****               ****           */ 
+ /*         ****                 ****          */ 
+ /*         ***                   ***          */ 
+ /*        ****                   ***          */ 
+ /*        ***                    ****         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                    ****         */ 
+ /*        *************          ****         */ 
+ /*         ************          ***          */ 
+ /*         ************         ****          */ 
+ /*         ************           *           */ 
+  0x05, 0x98, 0x01, 0x3d, 0x0d, 0xed, 0x4d, 0xad, 
+  0x7d, 0x97, 0x68, 0xd7, 0x5c, 0x6d, 0x55, 0xd2, 
+  0x4d, 0x54, 0xd4, 0x4d, 0x43, 0xd6, 0x3d, 0x34, 
+  0xd6, 0x3d, 0x33, 0xd7, 0x4d, 0x2e, 0x33, 0xd8, 
+  0x3d, 0x23, 0xd7, 0x4d, 0x2d, 0x0a, 0x4d, 0x3c, 
+  0xa3, 0xd4, 0xc9, 0x4d, 0x4c, 0xb1, 0x0a, 0x61, 
+
+
+ /* Char 72 is 28px wide @ 1362 */
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+  0x07, 0x9e, 0x2d, 0xed, 0xee, 0xc3, 0xde, 0xe2, 
+  0xde, 0x07, 0xa1, 
+
+ /* Char 73 is 12px wide @ 1373 */
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+  0x07, 0x9e, 0x2d, 0xe0, 0xce, 
+
+ /* Char 74 is 20px wide @ 1378 */
+ /*          *                                 */ 
+ /*         ****                               */ 
+ /*         ***                                */ 
+ /*        ****                                */ 
+ /*        ****                                */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ****                                */ 
+ /*         ***                                */ 
+ /*         *****                              */ 
+ /*          *************************         */ 
+ /*          *************************         */ 
+ /*           ************************         */ 
+ /*             **********************         */ 
+  0x91, 0x01, 0xc4, 0x01, 0xa3, 0x01, 0xaf, 0x40, 
+  0x1a, 0xe3, 0x30, 0x1b, 0x40, 0x1b, 0x30, 0x1b, 
+  0x50, 0x1a, 0xfd, 0xcd, 0x5d, 0xbd, 0x7d, 0x90, 
+  0x7a, 
+
+ /* Char 75 is 25px wide @ 1403 */
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*                    ****                    */ 
+ /*                   ******                   */ 
+ /*                  ********                  */ 
+ /*                  *********                 */ 
+ /*                 ***********                */ 
+ /*                ****** ******               */ 
+ /*               ******   ******              */ 
+ /*              ******     ******             */ 
+ /*             ******       ******            */ 
+ /*            ******         ******           */ 
+ /*           ******           ******          */ 
+ /*          ******             ******         */ 
+ /*        *******               *****         */ 
+ /*        ******                 ****         */ 
+ /*        *****                   ***         */ 
+ /*        ****                     **         */ 
+ /*        **                        *         */ 
+ /*        *                                   */ 
+  0x07, 0x9e, 0x2d, 0xed, 0xe4, 0x01, 0x96, 0x01, 
+  0x78, 0x01, 0x69, 0x01, 0x4b, 0x01, 0x26, 0x16, 
+  0xdf, 0x63, 0x6d, 0xd6, 0x56, 0xdb, 0x67, 0x6d, 
+  0x96, 0x96, 0xd7, 0x6b, 0x6d, 0x56, 0xd0, 0x6d, 
+  0x27, 0xd2, 0x5d, 0x26, 0xd4, 0x4d, 0x25, 0xd6, 
+  0x3d, 0x24, 0xd8, 0x2d, 0x22, 0xdb, 0x1d, 0x21, 
+  0x01, 0x61, 
+
+ /* Char 76 is 21px wide @ 1453 */
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+  0x07, 0x9e, 0x2d, 0xed, 0x2e, 0xa3, 0x06, 0x81, 
+
+
+ /* Char 77 is 34px wide @ 1461 */
+ /*        **********                          */ 
+ /*        ***********************             */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*                *******************         */ 
+ /*                            *******         */ 
+ /*                           *******          */ 
+ /*                         *******            */ 
+ /*                       *******              */ 
+ /*                    ********                */ 
+ /*                  ********                  */ 
+ /*                ********                    */ 
+ /*             ********                       */ 
+ /*            *******                         */ 
+ /*            ****                            */ 
+ /*            ****                            */ 
+ /*            *******                         */ 
+ /*             ********                       */ 
+ /*                ********                    */ 
+ /*                  ********                  */ 
+ /*                    ********                */ 
+ /*                       *******              */ 
+ /*                         *******            */ 
+ /*                           *******          */ 
+ /*                           ********         */ 
+ /*               ********************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        *********************               */ 
+ /*        ********                            */ 
+  0x04, 0xfa, 0x01, 0x4d, 0xad, 0x6f, 0xde, 0xda, 
+  0xd6, 0x01, 0x77, 0x01, 0x67, 0x01, 0x57, 0x01, 
+  0x57, 0x01, 0x48, 0x01, 0x48, 0x01, 0x48, 0x01, 
+  0x38, 0x01, 0x57, 0x01, 0x7f, 0x40, 0x1a, 0x70, 
+  0x18, 0x80, 0x19, 0x80, 0x18, 0x80, 0x18, 0x80, 
+  0x19, 0x70, 0x19, 0x70, 0x19, 0x70, 0x17, 0x8d, 
+  0x9d, 0x7d, 0x2f, 0xde, 0xd2, 0xd8, 0xd8, 0x80, 
+  0x63, 
+
+ /* Char 78 is 29px wide @ 1518 */
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*                            *******         */ 
+ /*                           *******          */ 
+ /*                          ******            */ 
+ /*                        *******             */ 
+ /*                       *******              */ 
+ /*                      ******                */ 
+ /*                    *******                 */ 
+ /*                   ******                   */ 
+ /*                 *******                    */ 
+ /*                ******                      */ 
+ /*              *******                       */ 
+ /*             ******                         */ 
+ /*           *******                          */ 
+ /*         *******                            */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+  0x07, 0x9e, 0x2d, 0xe0, 0x17, 0x70, 0x16, 0x70, 
+  0x16, 0x60, 0x16, 0x70, 0x16, 0x70, 0x16, 0x60, 
+  0x16, 0x70, 0x16, 0x60, 0x16, 0x70, 0x16, 0x60, 
+  0x16, 0x70, 0x16, 0x60, 0x16, 0x70, 0x15, 0x70, 
+  0x16, 0xe2, 0xde, 0x0a, 0x41, 
+
+ /* Char 79 is 31px wide @ 1555 */
+ /*                 *********                  */ 
+ /*               *************                */ 
+ /*             *****************              */ 
+ /*            *******************             */ 
+ /*           *******       *******            */ 
+ /*          ******           ******           */ 
+ /*          ****               ****           */ 
+ /*         ****                 ****          */ 
+ /*         ***                   ***          */ 
+ /*         ***                   ***          */ 
+ /*        ****                   ****         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ****                   ****         */ 
+ /*         ***                   ***          */ 
+ /*         ***                   ***          */ 
+ /*         ****                 ****          */ 
+ /*          ****               ****           */ 
+ /*          ******           ******           */ 
+ /*           ********     ********            */ 
+ /*            *******************             */ 
+ /*             *****************              */ 
+ /*               *************                */ 
+ /*                 *********                  */ 
+  0x05, 0x89, 0x01, 0x3d, 0x0d, 0xed, 0x4d, 0xbd, 
+  0x6d, 0x97, 0x77, 0xd7, 0x6b, 0x6d, 0x64, 0xd2, 
+  0x4d, 0x54, 0xd4, 0x4d, 0x4f, 0x3d, 0x63, 0xd3, 
+  0x4d, 0x64, 0xd2, 0xe2, 0x3d, 0x83, 0xd2, 0x4d, 
+  0x64, 0xd3, 0xf3, 0xd6, 0x3d, 0x44, 0xd4, 0x4d, 
+  0x54, 0xd2, 0x4d, 0x66, 0xb6, 0xd7, 0x85, 0x8d, 
+  0x9d, 0x6d, 0xbd, 0x4d, 0xed, 0x00, 0x13, 0x90, 
+  0x83, 
+
+ /* Char 80 is 24px wide @ 1612 */
+ /*        **************************          */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ****          ***         */ 
+ /*                  ****         ****         */ 
+ /*                   ***         ***          */ 
+ /*                   ****       ****          */ 
+ /*                   ******   *****           */ 
+ /*                    *************           */ 
+ /*                     ***********            */ 
+ /*                      *********             */ 
+ /*                        *****               */ 
+  0x07, 0x9d, 0xdd, 0x3e, 0x1d, 0xed, 0xce, 0x53, 
+  0xb3, 0xdc, 0x4a, 0x3d, 0xc4, 0x94, 0xdd, 0x39, 
+  0x3d, 0xe4, 0x74, 0xde, 0x63, 0x50, 0x11, 0xd0, 
+  0x01, 0x2b, 0x01, 0x49, 0x01, 0x75, 0x02, 0xc1, 
+
+
+ /* Char 81 is 31px wide @ 1644 */
+ /*                  ********                  */ 
+ /*               *************                */ 
+ /*             *****************              */ 
+ /*            *******************             */ 
+ /*           *******       *******            */ 
+ /*          ******           ******           */ 
+ /*          ****               ****           */ 
+ /*         ****                 ****          */ 
+ /*         ***                   ***          */ 
+ /*         ***                   ***          */ 
+ /*        ****                   ****         */ 
+ /*        ***                     ***         */ 
+ /*       ****                     ***         */ 
+ /*     ******                     ***         */ 
+ /*    *******                     ***         */ 
+ /*   *********                   ****         */ 
+ /*   **** ****                   ***          */ 
+ /*  ****   ***                   ***          */ 
+ /*  ***    ****                 ****          */ 
+ /*  ***    *****               ****           */ 
+ /* ****     ******           ******           */ 
+ /* ***       ********     ********            */ 
+ /* ***        *******************             */ 
+ /*  **         *****************              */ 
+ /*               *************                */ 
+ /*                  ********                  */ 
+  0x05, 0x98, 0x01, 0x3d, 0x0d, 0xed, 0x4d, 0xbd, 
+  0x6d, 0x97, 0x77, 0xd7, 0x6b, 0x6d, 0x64, 0xd2, 
+  0x4d, 0x54, 0xd4, 0x4d, 0x4f, 0x3d, 0x63, 0xd3, 
+  0x4d, 0x64, 0xd2, 0x3d, 0x83, 0xd1, 0x4d, 0x83, 
+  0xc6, 0xd8, 0x3b, 0x7d, 0x83, 0xa9, 0xd6, 0x4a, 
+  0x41, 0x4d, 0x63, 0xa4, 0x33, 0xd6, 0x3a, 0x34, 
+  0x4d, 0x44, 0xa3, 0x45, 0xd2, 0x4a, 0x45, 0x6b, 
+  0x6a, 0x37, 0x85, 0x8b, 0x38, 0xd6, 0xd0, 0x29, 
+  0xd4, 0xde, 0xd0, 0x01, 0x48, 0x08, 0x31, 
+
+ /* Char 82 is 25px wide @ 1715 */
+ /*        **************************          */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                  ***           ***         */ 
+ /*                 ****           ***         */ 
+ /*               *******         ****         */ 
+ /*              ********         ***          */ 
+ /*            ***********       ****          */ 
+ /*           ******  *****    ******          */ 
+ /*         *******    *************           */ 
+ /*        *******      ***********            */ 
+ /*        *****         *********             */ 
+ /*        ****           ******               */ 
+ /*        **                                  */ 
+ /*        *                                   */ 
+  0x07, 0x9d, 0xdd, 0x3e, 0x1d, 0xed, 0xce, 0x43, 
+  0xb3, 0xdb, 0x4b, 0x3d, 0x97, 0x94, 0xd8, 0x89, 
+  0x3d, 0x7b, 0x74, 0xd6, 0x62, 0x54, 0x6d, 0x47, 
+  0x4d, 0x0d, 0x47, 0x6b, 0xd5, 0x59, 0x9d, 0x64, 
+  0xb6, 0xd8, 0x20, 0x1c, 0x10, 0x40, 
+
+ /* Char 83 is 21px wide @ 1753 */
+ /*          *                                 */ 
+ /*         ****            ******             */ 
+ /*         ***            ********            */ 
+ /*         ***           **********           */ 
+ /*        ****          ************          */ 
+ /*        ***           *****   ****          */ 
+ /*        ***          *****     ****         */ 
+ /*        ***          ****      ****         */ 
+ /*        ***         *****       ***         */ 
+ /*        ***         ****        ***         */ 
+ /*        ***         ****        ***         */ 
+ /*        ***        ****         ***         */ 
+ /*        ****       ****         ***         */ 
+ /*         ***      *****         ***         */ 
+ /*         ****    *****         ****         */ 
+ /*         *************         ***          */ 
+ /*          ***********          ***          */ 
+ /*           *********            **          */ 
+ /*             *****                          */ 
+  0x02, 0x71, 0x01, 0xc4, 0xc6, 0xd7, 0x3c, 0x8d, 
+  0x63, 0xba, 0xd4, 0x4a, 0xcd, 0x33, 0xb5, 0x34, 
+  0xd3, 0x3a, 0x55, 0x4d, 0x23, 0xa4, 0x64, 0xd2, 
+  0x39, 0x57, 0x3d, 0x2f, 0x39, 0x48, 0x3d, 0x23, 
+  0x84, 0x93, 0xd2, 0x47, 0x49, 0x3d, 0x33, 0x65, 
+  0x93, 0xd3, 0x44, 0x59, 0x4d, 0x3d, 0x09, 0x3d, 
+  0x5b, 0xa3, 0xd6, 0x9c, 0x2d, 0x85, 0x03, 0x71, 
+
+
+ /* Char 84 is 23px wide @ 1809 */
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*        ***************************         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+ /*                                ***         */ 
+  0x03, 0xde, 0x73, 0xd2, 0xe2, 0xde, 0x01, 0xbe, 
+  0x63, 0x01, 0xb3, 0x81, 
+
+ /* Char 85 is 27px wide @ 1821 */
+ /*               ********************         */ 
+ /*             **********************         */ 
+ /*           ************************         */ 
+ /*          *************************         */ 
+ /*          *****                             */ 
+ /*         ****                               */ 
+ /*         ***                                */ 
+ /*        ****                                */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ****                                */ 
+ /*         ***                                */ 
+ /*         ****                               */ 
+ /*          *****                             */ 
+ /*          *************************         */ 
+ /*           ************************         */ 
+ /*             **********************         */ 
+ /*               ********************         */ 
+  0x08, 0x0d, 0x7d, 0x7d, 0x9d, 0x5d, 0xbd, 0x4d, 
+  0xcd, 0x45, 0x01, 0x84, 0x01, 0xa3, 0x01, 0xa4, 
+  0x01, 0xae, 0x33, 0x01, 0xb4, 0x01, 0xb3, 0x01, 
+  0xb4, 0x01, 0xb5, 0x01, 0x9d, 0xcd, 0x5d, 0xbd, 
+  0x7d, 0x9d, 0x9d, 0x70, 0x7a, 
+
+ /* Char 86 is 26px wide @ 1858 */
+ /*                                 **         */ 
+ /*                               ****         */ 
+ /*                            *******         */ 
+ /*                         **********         */ 
+ /*                       ***********          */ 
+ /*                    ************            */ 
+ /*                  ***********               */ 
+ /*                ***********                 */ 
+ /*             ***********                    */ 
+ /*           ***********                      */ 
+ /*         **********                         */ 
+ /*        *********                           */ 
+ /*        *******                             */ 
+ /*        *******                             */ 
+ /*        *********                           */ 
+ /*         **********                         */ 
+ /*           ***********                      */ 
+ /*             ***********                    */ 
+ /*                ***********                 */ 
+ /*                  ***********               */ 
+ /*                    ************            */ 
+ /*                       ***********          */ 
+ /*                         **********         */ 
+ /*                            *******         */ 
+ /*                               ****         */ 
+ /*                                 **         */ 
+  0x01, 0x42, 0x01, 0xa4, 0x01, 0x77, 0x01, 0x4a, 
+  0x01, 0x2b, 0xdf, 0xcd, 0xfb, 0x01, 0x1b, 0xdf, 
+  0xb0, 0x11, 0xb0, 0x11, 0xa0, 0x13, 0x90, 0x15, 
+  0xf7, 0x01, 0x79, 0x01, 0x6a, 0x01, 0x6b, 0x01, 
+  0x5b, 0x01, 0x6b, 0x01, 0x5b, 0x01, 0x5c, 0x01, 
+  0x5b, 0x01, 0x5a, 0x01, 0x77, 0x01, 0xa4, 0x01, 
+  0xc2, 0x81, 
+
+ /* Char 87 is 36px wide @ 1908 */
+ /*                               ****         */ 
+ /*                         **********         */ 
+ /*                    ***************         */ 
+ /*                *******************         */ 
+ /*           **********************           */ 
+ /*        *******************                 */ 
+ /*        **************                      */ 
+ /*        *********                           */ 
+ /*        ******                              */ 
+ /*        ********                            */ 
+ /*        ***********                         */ 
+ /*         **************                     */ 
+ /*            **************                  */ 
+ /*                **************              */ 
+ /*                   *************            */ 
+ /*                       *********            */ 
+ /*                         *******            */ 
+ /*                       *********            */ 
+ /*                   *************            */ 
+ /*                *************               */ 
+ /*             ************                   */ 
+ /*          ************                      */ 
+ /*        ***********                         */ 
+ /*        ********                            */ 
+ /*        ******                              */ 
+ /*        *********                           */ 
+ /*        **************                      */ 
+ /*        *******************                 */ 
+ /*            *********************           */ 
+ /*                *******************         */ 
+ /*                    ***************         */ 
+ /*                         **********         */ 
+ /*                               ****         */ 
+  0x03, 0xc4, 0x01, 0x4a, 0xde, 0xd2, 0xda, 0xd6, 
+  0xd5, 0xd9, 0xd4, 0xd6, 0xda, 0xd1, 0xdf, 0x90, 
+  0x15, 0x60, 0x18, 0x80, 0x16, 0xb0, 0x14, 0xd1, 
+  0x01, 0x3d, 0x10, 0x14, 0xd1, 0x01, 0x3d, 0x00, 
+  0x15, 0x90, 0x17, 0x70, 0x15, 0x90, 0x11, 0xd0, 
+  0xdd, 0xd0, 0xdd, 0xcd, 0xec, 0xdf, 0xb0, 0x13, 
+  0x80, 0x16, 0x60, 0x18, 0x90, 0x15, 0xd1, 0xdf, 
+  0xd6, 0xde, 0xd8, 0xdc, 0xd6, 0xde, 0xd2, 0x01, 
+  0x4a, 0x01, 0xa4, 0x05, 0x01, 
+
+ /* Char 88 is 25px wide @ 1977 */
+ /*        *                         *         */ 
+ /*        ***                      **         */ 
+ /*        ****                   ****         */ 
+ /*        ******                *****         */ 
+ /*        ********            *******         */ 
+ /*         ********          *******          */ 
+ /*           *******       *******            */ 
+ /*             *******    *******             */ 
+ /*              ******* *******               */ 
+ /*                ************                */ 
+ /*                 *********                  */ 
+ /*                  ********                  */ 
+ /*                 **********                 */ 
+ /*               **************               */ 
+ /*              *******  ********             */ 
+ /*            *******      *******            */ 
+ /*           *******        ********          */ 
+ /*         ********           *******         */ 
+ /*        *******              ******         */ 
+ /*        ******                 ****         */ 
+ /*        ****                     **         */ 
+ /*        **                        *         */ 
+ /*        *                                   */ 
+  0x02, 0x51, 0xdc, 0x1d, 0x23, 0xd9, 0x2d, 0x24, 
+  0xd6, 0x4d, 0x26, 0xd3, 0x5d, 0x28, 0xc7, 0xd3, 
+  0x8a, 0x7d, 0x67, 0x77, 0xda, 0x74, 0x7d, 0xc7, 
+  0x17, 0x01, 0x1c, 0x01, 0x39, 0x01, 0x68, 0x01, 
+  0x5a, 0x01, 0x2d, 0x1d, 0xe7, 0x28, 0xda, 0x76, 
+  0x7d, 0x87, 0x88, 0xd4, 0x8b, 0x7d, 0x27, 0xd1, 
+  0x6d, 0x26, 0xd4, 0x4d, 0x24, 0xd8, 0x2d, 0x22, 
+  0xdb, 0x1d, 0x21, 0x04, 0x01, 
+
+ /* Char 89 is 24px wide @ 2038 */
+ /*                                  *         */ 
+ /*                                ***         */ 
+ /*                               ****         */ 
+ /*                             ******         */ 
+ /*                           ********         */ 
+ /*                          *******           */ 
+ /*                        ********            */ 
+ /*                       *******              */ 
+ /*                     *******                */ 
+ /*                    *******                 */ 
+ /*        *****************                   */ 
+ /*        ****************                    */ 
+ /*        ****************                    */ 
+ /*        *****************                   */ 
+ /*                    *******                 */ 
+ /*                     *******                */ 
+ /*                       *******              */ 
+ /*                        ********            */ 
+ /*                          *******           */ 
+ /*                           ********         */ 
+ /*                             ******         */ 
+ /*                               ****         */ 
+ /*                                ***         */ 
+ /*                                  *         */ 
+  0x01, 0x51, 0x01, 0xb3, 0x01, 0xa4, 0x01, 0x86, 
+  0x01, 0x68, 0x01, 0x57, 0x01, 0x58, 0x01, 0x57, 
+  0x01, 0x57, 0x01, 0x67, 0xda, 0xd4, 0xdc, 0xfd, 
+  0x3d, 0xdd, 0x40, 0x19, 0x70, 0x18, 0x70, 0x19, 
+  0x70, 0x18, 0x80, 0x18, 0x70, 0x18, 0x80, 0x18, 
+  0x60, 0x1a, 0x40, 0x1b, 0x30, 0x1d, 0x18, 
+
+ /* Char 90 is 23px wide @ 2085 */
+ /*        ***                                 */ 
+ /*        ****                    ***         */ 
+ /*        ******                  ***         */ 
+ /*        ********                ***         */ 
+ /*        *********               ***         */ 
+ /*        ***********             ***         */ 
+ /*        ***  *******            ***         */ 
+ /*        ***    *******          ***         */ 
+ /*        ***     *******         ***         */ 
+ /*        ***       ******        ***         */ 
+ /*        ***        *******      ***         */ 
+ /*        ***          ******     ***         */ 
+ /*        ***           ******    ***         */ 
+ /*        ***            *******  ***         */ 
+ /*        ***              ****** ***         */ 
+ /*        ***               *********         */ 
+ /*        ***                ********         */ 
+ /*        ***                  ******         */ 
+ /*        ***                   *****         */ 
+ /*        ***                    ****         */ 
+  0x02, 0x53, 0x01, 0xb4, 0xd7, 0x3d, 0x26, 0xd5, 
+  0x3d, 0x28, 0xd3, 0x3d, 0x29, 0xd2, 0x3d, 0x2b, 
+  0xd0, 0x3d, 0x23, 0x27, 0xc3, 0xd2, 0x34, 0x7a, 
+  0x3d, 0x23, 0x57, 0x93, 0xd2, 0x37, 0x68, 0x3d, 
+  0x23, 0x87, 0x63, 0xd2, 0x3a, 0x65, 0x3d, 0x23, 
+  0xb6, 0x43, 0xd2, 0x3c, 0x72, 0x3d, 0x23, 0xd1, 
+  0x61, 0x3d, 0x23, 0xd2, 0x9d, 0x23, 0xd3, 0x8d, 
+  0x23, 0xd5, 0x6d, 0x23, 0xd6, 0x5d, 0x23, 0xd7, 
+  0x40, 0x50, 
+
+ /* Char 91 is 14px wide @ 2151 */
+ /* **************************************     */ 
+ /* **************************************     */ 
+ /* **************************************     */ 
+ /* **************************************     */ 
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+  0x09, 0xc0, 0x1a, 0xe2, 0x43, 0x01, 0x4e, 0x33, 
+  0x02, 0x21, 
+
+ /* Char 92 is 15px wide @ 2161 */
+ /*                                   ****     */ 
+ /*                                *******     */ 
+ /*                             *********      */ 
+ /*                          *********         */ 
+ /*                        *********           */ 
+ /*                     *********              */ 
+ /*                  *********                 */ 
+ /*               *********                    */ 
+ /*             *********                      */ 
+ /*          *********                         */ 
+ /*       *********                            */ 
+ /*     *********                              */ 
+ /*  *********                                 */ 
+ /* *******                                    */ 
+ /* ****                                       */ 
+  0x01, 0x64, 0x01, 0x77, 0x01, 0x49, 0x01, 0x29, 
+  0x01, 0x39, 0x01, 0x29, 0x01, 0x29, 0x01, 0x29, 
+  0x01, 0x39, 0x01, 0x29, 0x01, 0x29, 0x01, 0x39, 
+  0x01, 0x29, 0x01, 0x47, 0x01, 0x74, 0x01, 0xa1, 
+
+
+ /* Char 93 is 14px wide @ 2193 */
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+ /* **************************************     */ 
+ /* **************************************     */ 
+ /* **************************************     */ 
+ /* **************************************     */ 
+  0xe3, 0x01, 0x4e, 0x33, 0x40, 0x1a, 0xe2, 0x0c, 
+  0xa1, 
+
+ /* Char 94 is 23px wide @ 2202 */
+ /*                     *                      */ 
+ /*                     ***                    */ 
+ /*                    ******                  */ 
+ /*                     *******                */ 
+ /*                      *******               */ 
+ /*                        *******             */ 
+ /*                          *******           */ 
+ /*                            ******          */ 
+ /*                             ******         */ 
+ /*                               ****         */ 
+ /*                             ******         */ 
+ /*                            ******          */ 
+ /*                          *******           */ 
+ /*                        *******             */ 
+ /*                      *******               */ 
+ /*                     *******                */ 
+ /*                    ******                  */ 
+ /*                     ***                    */ 
+ /*                     *                      */ 
+  0x05, 0xc1, 0x01, 0xd3, 0x01, 0xa6, 0x01, 0x97, 
+  0x01, 0x87, 0x01, 0x97, 0x01, 0x97, 0x01, 0x96, 
+  0x01, 0x96, 0x01, 0xa4, 0x01, 0x86, 0x01, 0x76, 
+  0x01, 0x67, 0x01, 0x57, 0x01, 0x57, 0x01, 0x67, 
+  0x01, 0x66, 0x01, 0x93, 0x01, 0xb1, 0x05, 0xd1, 
+
+
+ /* Char 95 is 20px wide @ 2242 */
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+ /* ***                                        */ 
+  0xe3, 0xe0, 0x11, 0x04, 0x51, 
+
+ /* Char 96 is 15px wide @ 2247 */
+ /*                                    *       */ 
+ /*                                   ***      */ 
+ /*                                  *****     */ 
+ /*                                 *****      */ 
+ /*                                ****        */ 
+ /*                               ****         */ 
+ /*                                **          */ 
+  0x06, 0xb1, 0x01, 0xc3, 0x01, 0xa5, 0x01, 0x85, 
+  0x01, 0x84, 0x01, 0x94, 0x01, 0xb2, 0x0f, 0x91, 
+
+
+ /* Char 97 is 21px wide @ 2263 */
+ /*           ******                           */ 
+ /*          ********                          */ 
+ /*         **********     ***                 */ 
+ /*         **********     ****                */ 
+ /*        ****   *****     ***                */ 
+ /*        ****    ****     ***                */ 
+ /*        ***      ***     ***                */ 
+ /*        ***      ***     ***                */ 
+ /*        ***      ***     ***                */ 
+ /*        ***      ***    ****                */ 
+ /*        ***      ***   *****                */ 
+ /*        *******************                 */ 
+ /*        *******************                 */ 
+ /*        ******************                  */ 
+ /*         ***************                    */ 
+  0x05, 0x26, 0x01, 0x78, 0x01, 0x5a, 0x53, 0xdb, 
+  0xa5, 0x4d, 0x94, 0x35, 0x53, 0xd9, 0x44, 0x45, 
+  0x3d, 0x9e, 0x13, 0x63, 0x53, 0xd9, 0x36, 0x34, 
+  0x4d, 0x93, 0x63, 0x35, 0xd9, 0xfd, 0x6d, 0xad, 
+  0x5d, 0xcd, 0x20, 0xaf, 
+
+ /* Char 98 is 23px wide @ 2299 */
+ /*         *****************************      */ 
+ /*         *****************************      */ 
+ /*        ******************************      */ 
+ /*        ******************************      */ 
+ /*        ***             ***                 */ 
+ /*        ***             ***                 */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ****             ***                */ 
+ /*         ***            ****                */ 
+ /*         ****          ****                 */ 
+ /*          *****      ******                 */ 
+ /*          ****************                  */ 
+ /*           **************                   */ 
+ /*             ***********                    */ 
+ /*               *******                      */ 
+  0x07, 0xaf, 0x01, 0x1c, 0xf0, 0x12, 0xcf, 0x3d, 
+  0x03, 0xda, 0xe2, 0x3d, 0x13, 0xd9, 0x4d, 0x03, 
+  0xda, 0x3c, 0x4d, 0xa4, 0xa4, 0xdc, 0x56, 0x6d, 
+  0xcd, 0x3d, 0xed, 0x10, 0x12, 0xb0, 0x15, 0x70, 
+  0x5d, 
+
+ /* Char 99 is 19px wide @ 2332 */
+ /*              *******                       */ 
+ /*            ***********                     */ 
+ /*           **************                   */ 
+ /*          ****************                  */ 
+ /*         ******      ******                 */ 
+ /*         ****          ****                 */ 
+ /*        ****            ***                 */ 
+ /*        ****            ****                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ****            ****                */ 
+ /*         ***             **                 */ 
+  0x05, 0x57, 0x01, 0x5b, 0x01, 0x2d, 0x1d, 0xed, 
+  0x3d, 0xc6, 0x66, 0xdb, 0x4a, 0x4d, 0xa4, 0xc3, 
+  0xda, 0x4c, 0x4d, 0x9e, 0x33, 0xd1, 0x3d, 0x94, 
+  0xc4, 0xda, 0x3d, 0x02, 0x05, 0x81, 
+
+ /* Char 100 is 23px wide @ 2362 */
+ /*               *******                      */ 
+ /*             ***********                    */ 
+ /*           **************                   */ 
+ /*          ****************                  */ 
+ /*          *****      ******                 */ 
+ /*         ****          ****                 */ 
+ /*         ***            ****                */ 
+ /*        ****             ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***             ***                 */ 
+ /*        ***             ***                 */ 
+ /*        *****************************       */ 
+ /*        ******************************      */ 
+ /*         *****************************      */ 
+ /*         *****************************      */ 
+  0x05, 0x67, 0x01, 0x5b, 0x01, 0x1d, 0x1d, 0xed, 
+  0x3d, 0xd5, 0x66, 0xdb, 0x4a, 0x4d, 0xb3, 0xc4, 
+  0xd9, 0x4d, 0x03, 0xd9, 0xe2, 0x3d, 0x13, 0xd9, 
+  0xf3, 0xd0, 0x3d, 0xa0, 0x11, 0xd0, 0x01, 0x2d, 
+  0x0f, 0x01, 0x10, 0x77, 
+
+ /* Char 101 is 23px wide @ 2398 */
+ /*              *******                       */ 
+ /*            ************                    */ 
+ /*           **************                   */ 
+ /*          ****************                  */ 
+ /*          *****  ***  *****                 */ 
+ /*         ****    ***   ****                 */ 
+ /*         ***     ***    ****                */ 
+ /*        ****     ***     ***                */ 
+ /*        ***      ***     ***                */ 
+ /*        ***      ***     ***                */ 
+ /*        ***      ***     ***                */ 
+ /*        ***      ***    ****                */ 
+ /*        ***      ***    ****                */ 
+ /*        ***      ***  *****                 */ 
+ /*        ***      *********                  */ 
+ /*         ***     *********                  */ 
+ /*         ***     *******                    */ 
+ /*                 *****                      */ 
+  0x05, 0x57, 0x01, 0x5c, 0x01, 0x1d, 0x1d, 0xed, 
+  0x3d, 0xd5, 0x23, 0x25, 0xdb, 0x44, 0x33, 0x4d, 
+  0xb3, 0x53, 0x44, 0xd9, 0x45, 0x35, 0x3d, 0x9e, 
+  0x13, 0x63, 0x53, 0xd9, 0xf3, 0x63, 0x44, 0xd9, 
+  0x36, 0x32, 0x5d, 0xa3, 0x69, 0xdc, 0x35, 0x9d, 
+  0xc3, 0x57, 0x01, 0x75, 0x08, 0x71, 
+
+ /* Char 102 is 16px wide @ 2444 */
+ /*        *************************           */ 
+ /*        ***************************         */ 
+ /*        ****************************        */ 
+ /*        *****************************       */ 
+ /*                         ***    ******      */ 
+ /*                         ***      ****      */ 
+ /*                         ***       ***      */ 
+ /*                         ***       ***      */ 
+ /*                         ***       ***      */ 
+ /*                         ***       ***      */ 
+ /*                         ***       ***      */ 
+ /*                                   ***      */ 
+  0x07, 0x9d, 0xcd, 0x4d, 0xed, 0x2d, 0xfd, 0x10, 
+  0x11, 0x01, 0x23, 0x46, 0x01, 0x13, 0x64, 0x01, 
+  0x1e, 0x33, 0x73, 0x01, 0xb3, 0x02, 0x31, 
+
+ /* Char 103 is 23px wide @ 2467 */
+ /*               *******                      */ 
+ /*  ***        ***********                    */ 
+ /*  ***      **************                   */ 
+ /* ****      ***************                  */ 
+ /* ***      ******     *****                  */ 
+ /* ***      ****         ****                 */ 
+ /* ***     ****           ***                 */ 
+ /* ***     ***            ****                */ 
+ /* ***     ***             ***                */ 
+ /* ***     ***             ***                */ 
+ /* ***     ***             ***                */ 
+ /* ****    ***             ***                */ 
+ /*  ***     ***            ***                */ 
+ /*  *****   ***            ***                */ 
+ /*  **************************                */ 
+ /*   *************************                */ 
+ /*    ***********************                 */ 
+ /*      *********************                 */ 
+  0x05, 0x67, 0xd9, 0x38, 0xbd, 0x73, 0x6d, 0x1d, 
+  0x54, 0x6d, 0x2d, 0x43, 0x66, 0x55, 0xd4, 0x36, 
+  0x49, 0x4d, 0x33, 0x54, 0xb3, 0xd3, 0x35, 0x3c, 
+  0x4d, 0x23, 0x5e, 0x13, 0xd0, 0x3d, 0x24, 0x43, 
+  0xd0, 0x3d, 0x33, 0x53, 0xc3, 0xd3, 0x53, 0x3c, 
+  0x3d, 0x3d, 0xdd, 0x4d, 0xcd, 0x5d, 0xad, 0x8d, 
+  0x80, 0x82, 
+
+ /* Char 104 is 23px wide @ 2517 */
+ /*        ******************************      */ 
+ /*        ******************************      */ 
+ /*        ******************************      */ 
+ /*        ******************************      */ 
+ /*                        ***                 */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                        ****                */ 
+ /*                        ****                */ 
+ /*                      *****                 */ 
+ /*        *******************                 */ 
+ /*        ******************                  */ 
+ /*        *****************                   */ 
+ /*        ***************                     */ 
+  0x07, 0x9e, 0x20, 0x12, 0xdf, 0x30, 0x1c, 0xe3, 
+  0x30, 0x1a, 0xf4, 0x01, 0x85, 0xda, 0xd6, 0xda, 
+  0xd5, 0xdb, 0xd4, 0xdc, 0xd2, 0x08, 0x61, 
+
+ /* Char 105 is 11px wide @ 2540 */
+ /*        ********************     ****       */ 
+ /*        ********************     ****       */ 
+ /*        ********************     ****       */ 
+ /*        ********************     ****       */ 
+  0x07, 0x9e, 0x2d, 0x75, 0x40, 0xa2, 
+
+ /* Char 106 is 11px wide @ 2546 */
+ /* ***                                        */ 
+ /* ****                                       */ 
+ /* *****                                      */ 
+ /*  **************************     ****       */ 
+ /*  **************************     ****       */ 
+ /*   *************************     ****       */ 
+ /*     ***********************     ****       */ 
+  0xe3, 0x01, 0xb4, 0x01, 0xa5, 0x01, 0xaf, 0xdd, 
+  0x54, 0x8d, 0xc5, 0x4a, 0xda, 0x54, 0x0a, 0x21, 
+
+
+ /* Char 107 is 21px wide @ 2562 */
+ /*        ******************************      */ 
+ /*        ******************************      */ 
+ /*        ******************************      */ 
+ /*        ******************************      */ 
+ /*                 ****                       */ 
+ /*                ******                      */ 
+ /*               ********                     */ 
+ /*              ***********                   */ 
+ /*            **************                  */ 
+ /*          ********   ******                 */ 
+ /*        *********     ******                */ 
+ /*        ********       *****                */ 
+ /*        ******          ****                */ 
+ /*        *****             **                */ 
+ /*        ***                *                */ 
+ /*        *                                   */ 
+  0x07, 0x9e, 0x20, 0x12, 0xd8, 0x40, 0x19, 0x60, 
+  0x17, 0x80, 0x15, 0xb0, 0x11, 0xd1, 0xdd, 0x83, 
+  0x6d, 0xa9, 0x56, 0xd9, 0x87, 0x5d, 0x96, 0xa4, 
+  0xd9, 0x5d, 0x02, 0xd9, 0x3d, 0x31, 0xd9, 0x10, 
+  0x6a, 
+
+ /* Char 108 is 11px wide @ 2595 */
+ /*           ***************************      */ 
+ /*         *****************************      */ 
+ /*         *****************************      */ 
+ /*        ******************************      */ 
+ /*        ****                                */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+  0x07, 0xcd, 0xed, 0x0f, 0x01, 0x1c, 0x01, 0x2c, 
+  0x40, 0x1a, 0xf3, 0x03, 0xe1, 
+
+ /* Char 109 is 34px wide @ 2608 */
+ /*        *******************                 */ 
+ /*        *******************                 */ 
+ /*        ********************                */ 
+ /*        ********************                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                        ****                */ 
+ /*                      *****                 */ 
+ /*        *******************                 */ 
+ /*        ******************                  */ 
+ /*        ******************                  */ 
+ /*        *******************                 */ 
+ /*                        ***                 */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                        ****                */ 
+ /*                      ******                */ 
+ /*        *******************                 */ 
+ /*        ******************                  */ 
+ /*        *****************                   */ 
+ /*        ***************                     */ 
+  0x07, 0x9f, 0xd6, 0xda, 0xfd, 0x70, 0x1b, 0xe4, 
+  0x30, 0x1a, 0x40, 0x18, 0x5d, 0xad, 0x6d, 0xaf, 
+  0xd5, 0xdb, 0xd6, 0x01, 0xb3, 0x01, 0xce, 0x33, 
+  0x01, 0xa4, 0x01, 0x86, 0xd9, 0xd6, 0xda, 0xd5, 
+  0xdb, 0xd4, 0xdc, 0xd2, 0x08, 0x61, 
+
+ /* Char 110 is 23px wide @ 2646 */
+ /*        *******************                 */ 
+ /*        *******************                 */ 
+ /*        ********************                */ 
+ /*        ********************                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                        ****                */ 
+ /*                      *****                 */ 
+ /*        *******************                 */ 
+ /*        ******************                  */ 
+ /*        *****************                   */ 
+ /*        ***************                     */ 
+  0x07, 0x9f, 0xd6, 0xda, 0xfd, 0x70, 0x1b, 0xe4, 
+  0x30, 0x1a, 0x40, 0x18, 0x5d, 0xad, 0x6d, 0xad, 
+  0x5d, 0xbd, 0x4d, 0xcd, 0x20, 0xb0, 
+
+ /* Char 111 is 23px wide @ 2668 */
+ /*               ******                       */ 
+ /*             **********                     */ 
+ /*           **************                   */ 
+ /*          ****************                  */ 
+ /*         ******      ******                 */ 
+ /*         ****          ****                 */ 
+ /*        ****            ***                 */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ****            ***                 */ 
+ /*         ****          ****                 */ 
+ /*         ******      ******                 */ 
+ /*          ****************                  */ 
+ /*           **************                   */ 
+ /*             **********                     */ 
+ /*               ******                       */ 
+  0x05, 0x66, 0x01, 0x6a, 0x01, 0x2d, 0x1d, 0xed, 
+  0x3d, 0xc6, 0x66, 0xdb, 0x4a, 0x4d, 0xa4, 0xc3, 
+  0xda, 0xe3, 0x3d, 0x13, 0xd9, 0x4c, 0x3d, 0xb4, 
+  0xa4, 0xdb, 0x66, 0x6d, 0xcd, 0x3d, 0xed, 0x10, 
+  0x12, 0xa0, 0x16, 0x60, 0x5e, 
+
+ /* Char 112 is 23px wide @ 2705 */
+ /* **************************                 */ 
+ /* **************************                 */ 
+ /* ***************************                */ 
+ /* ***************************                */ 
+ /*         ***             ***                */ 
+ /*         ***             ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***             ****                */ 
+ /*        ****            ***                 */ 
+ /*         ****          ****                 */ 
+ /*         ******      *****                  */ 
+ /*          ****************                  */ 
+ /*           **************                   */ 
+ /*            ***********                     */ 
+ /*              *******                       */ 
+  0x07, 0x2d, 0xdf, 0xd3, 0xde, 0xfd, 0xaf, 0x3d, 
+  0x03, 0xd9, 0xe2, 0x3d, 0x13, 0xd9, 0x3d, 0x04, 
+  0xd9, 0x4c, 0x3d, 0xb4, 0xa4, 0xdb, 0x66, 0x5d, 
+  0xdd, 0x3d, 0xed, 0x10, 0x11, 0xb0, 0x15, 0x70, 
+  0x5e, 
+
+ /* Char 113 is 23px wide @ 2738 */
+ /*              *******                       */ 
+ /*            ***********                     */ 
+ /*           **************                   */ 
+ /*          ****************                  */ 
+ /*         ******      *****                  */ 
+ /*         ****          ****                 */ 
+ /*        ****            ***                 */ 
+ /*        ***             ****                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*         ***             ***                */ 
+ /*         ***             ***                */ 
+ /* ***************************                */ 
+ /* ***************************                */ 
+ /* **************************                 */ 
+ /* **************************                 */ 
+  0x05, 0x57, 0x01, 0x5b, 0x01, 0x2d, 0x1d, 0xed, 
+  0x3d, 0xc6, 0x65, 0xdc, 0x4a, 0x4d, 0xa4, 0xc3, 
+  0xda, 0x3d, 0x04, 0xd9, 0xe2, 0x3d, 0x13, 0xda, 
+  0xf3, 0xd0, 0x3d, 0x2d, 0xef, 0xd2, 0xdd, 0xf0, 
+  0x82, 
+
+ /* Char 114 is 16px wide @ 2771 */
+ /*        *******************                 */ 
+ /*        *******************                 */ 
+ /*        *******************                 */ 
+ /*        ********************                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+ /*                         ***                */ 
+  0x07, 0x9e, 0x1d, 0x6d, 0xad, 0x70, 0x1b, 0xe6, 
+  0x30, 0x2d, 
+
+ /* Char 115 is 18px wide @ 2781 */
+ /*         ***       ******                   */ 
+ /*         ***      ********                  */ 
+ /*        ***      **********                 */ 
+ /*        ***      **********                 */ 
+ /*        ***      ****  *****                */ 
+ /*        ***     ****     ***                */ 
+ /*        ***     ****     ***                */ 
+ /*        ***     ****     ***                */ 
+ /*        ****  *****      ***                */ 
+ /*         **********      ***                */ 
+ /*         **********     ****                */ 
+ /*          ********      ***                 */ 
+ /*           *****                            */ 
+  0x05, 0x03, 0x76, 0xdd, 0x36, 0x8d, 0xbf, 0x36, 
+  0xad, 0xa3, 0x64, 0x25, 0xd9, 0xe1, 0x35, 0x45, 
+  0x3d, 0x94, 0x25, 0x63, 0xda, 0xa6, 0x3d, 0xaa, 
+  0x54, 0xdb, 0x86, 0x3d, 0xd5, 0x08, 0xd1, 
+
+ /* Char 116 is 16px wide @ 2812 */
+ /*            **********************          */ 
+ /*          ************************          */ 
+ /*         *************************          */ 
+ /*         *************************          */ 
+ /*        *****            ***                */ 
+ /*        ****             ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ****             ***                */ 
+ /*         **                                 */ 
+  0x07, 0xdd, 0x9d, 0x5d, 0xbd, 0x4f, 0xdc, 0xd3, 
+  0x5c, 0x3d, 0x94, 0xd0, 0x3d, 0x9e, 0x23, 0xd1, 
+  0x3d, 0x94, 0xd0, 0x3d, 0xa2, 0x03, 0xe1, 
+
+ /* Char 117 is 23px wide @ 2835 */
+ /*             ***************                */ 
+ /*           *****************                */ 
+ /*          ******************                */ 
+ /*         *******************                */ 
+ /*         *****                              */ 
+ /*        ****                                */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ********************                */ 
+ /*        ********************                */ 
+ /*         *******************                */ 
+ /*         *******************                */ 
+  0x07, 0xed, 0x2d, 0xcd, 0x4d, 0xbd, 0x5d, 0xad, 
+  0x6d, 0xa5, 0x01, 0x84, 0x01, 0xae, 0x43, 0x01, 
+  0xbf, 0xd7, 0xda, 0xfd, 0x60, 0xab, 
+
+ /* Char 118 is 20px wide @ 2857 */
+ /*                          **                */ 
+ /*                        ****                */ 
+ /*                     *******                */ 
+ /*                  **********                */ 
+ /*               ************                 */ 
+ /*             ***********                    */ 
+ /*           **********                       */ 
+ /*         **********                         */ 
+ /*        ********                            */ 
+ /*        ******                              */ 
+ /*        ******                              */ 
+ /*        ********                            */ 
+ /*         **********                         */ 
+ /*           **********                       */ 
+ /*             ***********                    */ 
+ /*               ************                 */ 
+ /*                  **********                */ 
+ /*                     *******                */ 
+ /*                        ****                */ 
+  0x03, 0x72, 0x01, 0xa4, 0x01, 0x77, 0x01, 0x4a, 
+  0x01, 0x1c, 0xdf, 0xb0, 0x11, 0xa0, 0x12, 0xa0, 
+  0x13, 0x80, 0x16, 0xf6, 0x01, 0x88, 0x01, 0x7a, 
+  0x01, 0x6a, 0x01, 0x6b, 0x01, 0x5c, 0x01, 0x5a, 
+  0x01, 0x77, 0x01, 0xa4, 0xd2, 
+
+ /* Char 119 is 31px wide @ 2894 */
+ /*                          **                */ 
+ /*                       *****                */ 
+ /*                   *********                */ 
+ /*                ************                */ 
+ /*             **************                 */ 
+ /*          ************                      */ 
+ /*        ***********                         */ 
+ /*        *******                             */ 
+ /*        *****                               */ 
+ /*        ********                            */ 
+ /*        ***********                         */ 
+ /*           ************                     */ 
+ /*              *************                 */ 
+ /*                  **********                */ 
+ /*                     *******                */ 
+ /*                  **********                */ 
+ /*              **************                */ 
+ /*           ************                     */ 
+ /*        ***********                         */ 
+ /*        ********                            */ 
+ /*        *****                               */ 
+ /*        *******                             */ 
+ /*        ***********                         */ 
+ /*          *************                     */ 
+ /*             **************                 */ 
+ /*                ************                */ 
+ /*                   *********                */ 
+ /*                       *****                */ 
+ /*                          **                */ 
+  0x03, 0x72, 0x01, 0x95, 0x01, 0x59, 0x01, 0x2c, 
+  0xde, 0xd1, 0xdc, 0xcd, 0xfb, 0x01, 0x37, 0x01, 
+  0x75, 0x01, 0x98, 0x01, 0x6b, 0x01, 0x6c, 0x01, 
+  0x5d, 0x00, 0x15, 0xa0, 0x17, 0x70, 0x14, 0xad, 
+  0xfd, 0x1d, 0xcc, 0xde, 0xb0, 0x13, 0x80, 0x16, 
+  0x50, 0x19, 0x70, 0x17, 0xb0, 0x15, 0xd0, 0x01, 
+  0x4d, 0x10, 0x13, 0xc0, 0x15, 0x90, 0x19, 0x50, 
+  0x1c, 0x20, 0x2d, 
+
+ /* Char 120 is 21px wide @ 2953 */
+ /*        *                  *                */ 
+ /*        ***               **                */ 
+ /*        *****           ****                */ 
+ /*        ******         *****                */ 
+ /*        ********     *******                */ 
+ /*         ********   *******                 */ 
+ /*           **************                   */ 
+ /*             ***********                    */ 
+ /*              ********                      */ 
+ /*              *********                     */ 
+ /*            *************                   */ 
+ /*           ******* ********                 */ 
+ /*         ********    *******                */ 
+ /*        *******       ******                */ 
+ /*        ******          ****                */ 
+ /*        ****             ***                */ 
+ /*        ***                *                */ 
+ /*        *                                   */ 
+  0x02, 0x51, 0xd5, 0x1d, 0x93, 0xd2, 0x2d, 0x95, 
+  0xb4, 0xd9, 0x69, 0x5d, 0x98, 0x57, 0xda, 0x83, 
+  0x7d, 0xdd, 0x10, 0x12, 0xb0, 0x14, 0x80, 0x16, 
+  0x90, 0x13, 0xd0, 0xdf, 0x71, 0x8d, 0xb8, 0x47, 
+  0xd9, 0x77, 0x6d, 0x96, 0xa4, 0xd9, 0x4d, 0x03, 
+  0xd9, 0x3d, 0x31, 0xd9, 0x10, 0x6a, 
+
+ /* Char 121 is 20px wide @ 2999 */
+ /* ***                                        */ 
+ /* ***                      **                */ 
+ /* ***                   *****                */ 
+ /* ***                ********                */ 
+ /* ***             ***********                */ 
+ /* ****         *************                 */ 
+ /* ****      *************                    */ 
+ /*  ****  *************                       */ 
+ /*  ***************                           */ 
+ /*   ***********                              */ 
+ /*    ********                                */ 
+ /*     ************                           */ 
+ /*       *************                        */ 
+ /*          **************                    */ 
+ /*             **************                 */ 
+ /*                ************                */ 
+ /*                    ********                */ 
+ /*                       *****                */ 
+ /*                          **                */ 
+  0xe3, 0x01, 0xb3, 0xd9, 0x2d, 0x23, 0xd6, 0x5d, 
+  0x23, 0xd3, 0x8d, 0x23, 0xd0, 0xbd, 0x24, 0x9d, 
+  0x0d, 0x34, 0x6d, 0x0d, 0x74, 0x2d, 0x0d, 0xad, 
+  0x2d, 0xfb, 0x01, 0x48, 0x01, 0x7c, 0x01, 0x4d, 
+  0x00, 0x14, 0xd1, 0x01, 0x3d, 0x10, 0x13, 0xc0, 
+  0x16, 0x80, 0x19, 0x50, 0x1c, 0x20, 0x2d, 
+
+ /* Char 122 is 19px wide @ 3046 */
+ /*        ***                                 */ 
+ /*        ****             ***                */ 
+ /*        ******           ***                */ 
+ /*        *******          ***                */ 
+ /*        *********        ***                */ 
+ /*        **********       ***                */ 
+ /*        *** *******      ***                */ 
+ /*        ***   *******    ***                */ 
+ /*        ***    *******   ***                */ 
+ /*        ***      ******  ***                */ 
+ /*        ***       ****** ***                */ 
+ /*        ***        *********                */ 
+ /*        ***          *******                */ 
+ /*        ***           ******                */ 
+ /*        ***            *****                */ 
+ /*        ***             ****                */ 
+  0x02, 0x53, 0x01, 0xb4, 0xd0, 0x3d, 0x96, 0xb3, 
+  0xd9, 0x7a, 0x3d, 0x99, 0x83, 0xd9, 0xa7, 0x3d, 
+  0x93, 0x17, 0x63, 0xd9, 0x33, 0x74, 0x3d, 0x93, 
+  0x47, 0x33, 0xd9, 0x36, 0x62, 0x3d, 0x93, 0x76, 
+  0x13, 0xd9, 0x38, 0x9d, 0x93, 0xa7, 0xd9, 0x3b, 
+  0x6d, 0x93, 0xc5, 0xd9, 0x3d, 0x04, 0x05, 0x71, 
+
+
+ /* Char 123 is 14px wide @ 3094 */
+ /*                   ***                      */ 
+ /*                   ***                      */ 
+ /*                  *****                     */ 
+ /*                 *******                    */ 
+ /*     *******************************        */ 
+ /*   **********************************       */ 
+ /*  *****************   ****************      */ 
+ /*  ****************     ***************      */ 
+ /* *****                            *****     */ 
+ /* ****                              ****     */ 
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+  0x03, 0x0f, 0x30, 0x1a, 0x50, 0x18, 0x7d, 0xa0, 
+  0x13, 0x90, 0x16, 0x7d, 0x43, 0xd3, 0x6d, 0x35, 
+  0xd2, 0x55, 0xdf, 0x54, 0x40, 0x12, 0x44, 0x30, 
+  0x14, 0xf3, 0x02, 0x21, 
+
+ /* Char 124 is 12px wide @ 3122 */
+ /* **************************************     */ 
+ /* **************************************     */ 
+ /* **************************************     */ 
+  0x09, 0xc0, 0x1a, 0xe1, 0x0c, 0xa1, 
+
+ /* Char 125 is 14px wide @ 3128 */
+ /* ***                                ***     */ 
+ /* ***                                ***     */ 
+ /* ****                              ****     */ 
+ /* *****                            *****     */ 
+ /*  ****************     ***************      */ 
+ /*  *****************   ****************      */ 
+ /*   **********************************       */ 
+ /*     *******************************        */ 
+ /*                 *******                    */ 
+ /*                  *****                     */ 
+ /*                   ***                      */ 
+ /*                   ***                      */ 
+  0xe3, 0x01, 0x4f, 0x34, 0x40, 0x12, 0x44, 0x5d, 
+  0xf5, 0x5d, 0x35, 0xd2, 0x6d, 0x43, 0xd3, 0x70, 
+  0x16, 0xa0, 0x13, 0xda, 0x70, 0x18, 0x50, 0x1a, 
+  0xf3, 0x05, 0xd1, 
+
+ /* Char 126 is 23px wide @ 3155 */
+ /*                  *                         */ 
+ /*                 ****                       */ 
+ /*                 *****                      */ 
+ /*                  *****                     */ 
+ /*                   ****                     */ 
+ /*                    ***                     */ 
+ /*                    ***                     */ 
+ /*                   ****                     */ 
+ /*                   ***                      */ 
+ /*                  ****                      */ 
+ /*                  ***                       */ 
+ /*                 ****                       */ 
+ /*                 ***                        */ 
+ /*                 ***                        */ 
+ /*                 ***                        */ 
+ /*                 *****                      */ 
+ /*                  *****                     */ 
+ /*                   ****                     */ 
+ /*                     *                      */ 
+  0x05, 0x91, 0x01, 0xc4, 0x01, 0xa5, 0x01, 0xa5, 
+  0x01, 0xa4, 0x01, 0xbf, 0x30, 0x1a, 0x40, 0x1a, 
+  0x30, 0x1a, 0x40, 0x1a, 0x30, 0x1a, 0x40, 0x1a, 
+  0xe1, 0x30, 0x1b, 0x50, 0x1a, 0x50, 0x1a, 0x40, 
+  0x1c, 0x10, 0x5d, 
+
+ /* Char 196 is 26px wide @ 3190 */
+ /*        **                                  */ 
+ /*        ****                                */ 
+ /*        *******                             */ 
+ /*        **********                          */ 
+ /*         ************                       */ 
+ /*           *************                    */ 
+ /*              ************             ***  */ 
+ /*               **************         ***** */ 
+ /*               ***  ************      ***** */ 
+ /*               ***    *************   ***** */ 
+ /*               ***       **********    ***  */ 
+ /*               ***          *******         */ 
+ /*               ***            *****         */ 
+ /*               ***          *******         */ 
+ /*               ***        *********    ***  */ 
+ /*               ***     ***********    ***** */ 
+ /*               ***   ***********      ***** */ 
+ /*               **************         ***** */ 
+ /*               ************            ***  */ 
+ /*             ***********                    */ 
+ /*           ***********                      */ 
+ /*        ***********                         */ 
+ /*        *********                           */ 
+ /*        ******                              */ 
+ /*        ****                                */ 
+ /*        *                                   */ 
+  0x72, 0x01, 0xc4, 0x01, 0xa7, 0x01, 0x7a, 0x01, 
+  0x5c, 0x01, 0x4d, 0x00, 0x14, 0xcd, 0x03, 0xd2, 
+  0xd1, 0x95, 0xd1, 0x32, 0xc6, 0x5d, 0x13, 0x4d, 
+  0x03, 0x5d, 0x13, 0x7a, 0x43, 0xd2, 0x3a, 0x7d, 
+  0x93, 0xc5, 0xd9, 0x3a, 0x7d, 0x93, 0x89, 0x43, 
+  0xd2, 0x35, 0xb4, 0x5d, 0x13, 0x3b, 0x65, 0xd1, 
+  0xd1, 0x95, 0xd1, 0xcc, 0x3d, 0x0b, 0x01, 0x1b, 
+  0xdf, 0xb0, 0x13, 0x90, 0x15, 0x60, 0x18, 0x40, 
+  0x1a, 0x10, 0x16, 
+
+ /* Char 214 is 31px wide @ 3257 */
+ /*                 *********                  */ 
+ /*               *************                */ 
+ /*             *****************              */ 
+ /*            *******************             */ 
+ /*           *******       *******            */ 
+ /*          ******           ******           */ 
+ /*          ****               ****      ***  */ 
+ /*         ****                 ****    ***** */ 
+ /*         ***                   ***    ***** */ 
+ /*         ***                   ***    ***** */ 
+ /*        ****                   ****    ***  */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***         */ 
+ /*        ***                     ***    ***  */ 
+ /*        ****                   ****   ***** */ 
+ /*         ***                   ***    ***** */ 
+ /*         ***                   ***    ***** */ 
+ /*         ****                 ****     ***  */ 
+ /*          ****               ****           */ 
+ /*          ******           ******           */ 
+ /*           ********     ********            */ 
+ /*            *******************             */ 
+ /*             *****************              */ 
+ /*               *************                */ 
+ /*                 *********                  */ 
+  0x05, 0x89, 0x01, 0x3d, 0x0d, 0xed, 0x4d, 0xbd, 
+  0x6d, 0x97, 0x77, 0xd7, 0x6b, 0x6d, 0x64, 0xd2, 
+  0x46, 0x39, 0x4d, 0x44, 0x45, 0x8f, 0x3d, 0x63, 
+  0x45, 0x74, 0xd6, 0x44, 0x38, 0xe1, 0x3d, 0x83, 
+  0xd2, 0x3d, 0x83, 0x43, 0x84, 0xd6, 0x43, 0x58, 
+  0xf3, 0xd6, 0x34, 0x58, 0x4d, 0x44, 0x53, 0xa4, 
+  0xd2, 0x4d, 0x66, 0xb6, 0xd7, 0x85, 0x8d, 0x9d, 
+  0x6d, 0xbd, 0x4d, 0xed, 0x00, 0x13, 0x90, 0x83, 
+
+
+ /* Char 220 is 27px wide @ 3321 */
+ /*               ********************         */ 
+ /*             **********************         */ 
+ /*           ************************         */ 
+ /*          *************************         */ 
+ /*          *****                        ***  */ 
+ /*         ****                         ***** */ 
+ /*         ***                          ***** */ 
+ /*        ****                          ***** */ 
+ /*        ***                            ***  */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                            ***  */ 
+ /*        ****                          ***** */ 
+ /*         ***                          ***** */ 
+ /*         ****                         ***** */ 
+ /*          *****                        ***  */ 
+ /*          *************************         */ 
+ /*           ************************         */ 
+ /*             **********************         */ 
+ /*               ********************         */ 
+  0x08, 0x0d, 0x7d, 0x7d, 0x9d, 0x5d, 0xbd, 0x4d, 
+  0xcd, 0x45, 0xdb, 0x39, 0x4d, 0xc5, 0x83, 0xdd, 
+  0x57, 0x4d, 0xd5, 0x73, 0xdf, 0x38, 0xe1, 0x30, 
+  0x1b, 0x3d, 0xf3, 0x84, 0xdd, 0x58, 0x3d, 0xd5, 
+  0x84, 0xdc, 0x59, 0x5d, 0xb3, 0xad, 0xcd, 0x5d, 
+  0xbd, 0x7d, 0x9d, 0x9d, 0x70, 0x7a, 
+
+ /* Char 223 is 25px wide @ 3367 */
+ /*        *************************           */ 
+ /*        ***************************         */ 
+ /*        ****************************        */ 
+ /*        *****************************       */ 
+ /*                                *****       */ 
+ /*                                  ****      */ 
+ /*                                  ****      */ 
+ /*         ***                       ***      */ 
+ /*        ****         ***           ***      */ 
+ /*        ****        ******         ***      */ 
+ /*        ***        ********        ***      */ 
+ /*        ***       **********      ****      */ 
+ /*        ***       *****  *****   *****      */ 
+ /*        ***      *****    ***********       */ 
+ /*        ****     ****      **********       */ 
+ /*        *****  ******       ********        */ 
+ /*         ***********          ****          */ 
+ /*         ***********                        */ 
+ /*          *********                         */ 
+ /*            *****                           */ 
+  0x07, 0x9d, 0xcd, 0x4d, 0xed, 0x2d, 0xfd, 0x10, 
+  0x11, 0x01, 0x95, 0x01, 0xbf, 0x4d, 0x03, 0xda, 
+  0x3c, 0x49, 0x3b, 0x3c, 0x48, 0x69, 0x3c, 0x38, 
+  0x88, 0x3c, 0x37, 0xa6, 0x4c, 0x37, 0x52, 0x53, 
+  0x5c, 0x36, 0x54, 0xbd, 0x04, 0x54, 0x6a, 0xd0, 
+  0x52, 0x67, 0x8d, 0x2b, 0xa4, 0xd4, 0xb0, 0x14, 
+  0x90, 0x17, 0x50, 0x62, 
+
+ /* Char 228 is 21px wide @ 3419 */
+ /*           ******                           */ 
+ /*          ********                          */ 
+ /*         **********     ***      ***        */ 
+ /*         **********     ****    *****       */ 
+ /*        ****   *****     ***    *****       */ 
+ /*        ****    ****     ***    *****       */ 
+ /*        ***      ***     ***     ***        */ 
+ /*        ***      ***     ***                */ 
+ /*        ***      ***     ***                */ 
+ /*        ***      ***    ****                */ 
+ /*        ***      ***   *****     ***        */ 
+ /*        *******************     *****       */ 
+ /*        *******************     *****       */ 
+ /*        ******************      *****       */ 
+ /*         ***************         ***        */ 
+  0x05, 0x26, 0x01, 0x78, 0x01, 0x5a, 0x53, 0x63, 
+  0xd2, 0xa5, 0x44, 0x5d, 0x04, 0x35, 0x53, 0x45, 
+  0xd0, 0x44, 0x45, 0x34, 0x5d, 0x03, 0x63, 0x53, 
+  0x53, 0xd1, 0xf3, 0x63, 0x53, 0xd9, 0x36, 0x34, 
+  0x4d, 0x93, 0x63, 0x35, 0x53, 0xd1, 0xfd, 0x65, 
+  0x5d, 0x0d, 0x56, 0x5d, 0x1d, 0x29, 0x30, 0xa3, 
+
+
+ /* Char 246 is 23px wide @ 3467 */
+ /*               ******                       */ 
+ /*             **********                     */ 
+ /*           **************                   */ 
+ /*          ****************       ***        */ 
+ /*         ******      ******     *****       */ 
+ /*         ****          ****     *****       */ 
+ /*        ****            ***     *****       */ 
+ /*        ***              ***     ***        */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***                */ 
+ /*        ***              ***     ***        */ 
+ /*        ****            ***     *****       */ 
+ /*         ****          ****     *****       */ 
+ /*         ******      ******     *****       */ 
+ /*          ****************       ***        */ 
+ /*           **************                   */ 
+ /*             **********                     */ 
+ /*               ******                       */ 
+  0x05, 0x66, 0x01, 0x6a, 0x01, 0x2d, 0x1d, 0xed, 
+  0x37, 0x3d, 0x26, 0x66, 0x55, 0xd1, 0x4a, 0x45, 
+  0x5d, 0x04, 0xc3, 0x55, 0xd0, 0x3d, 0x13, 0x53, 
+  0xd1, 0xe1, 0x3d, 0x13, 0xd9, 0x3d, 0x13, 0x53, 
+  0xd1, 0x4c, 0x35, 0x5d, 0x14, 0xa4, 0x55, 0xd1, 
+  0x66, 0x65, 0x5d, 0x2d, 0x37, 0x3d, 0x4d, 0x10, 
+  0x12, 0xa0, 0x16, 0x60, 0x5e, 
+
+ /* Char 252 is 23px wide @ 3520 */
+ /*             ***************                */ 
+ /*           *****************     ***        */ 
+ /*          ******************    *****       */ 
+ /*         *******************    *****       */ 
+ /*         *****                  *****       */ 
+ /*        ****                     ***        */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                                 */ 
+ /*        ***                      ***        */ 
+ /*        ***                     *****       */ 
+ /*        ***                     *****       */ 
+ /*        ********************    *****       */ 
+ /*        ********************     ***        */ 
+ /*         *******************                */ 
+ /*         *******************                */ 
+  0x07, 0xed, 0x2d, 0xcd, 0x45, 0x3d, 0x3d, 0x54, 
+  0x5d, 0x1d, 0x64, 0x5d, 0x15, 0xd5, 0x5d, 0x04, 
+  0xd8, 0x3d, 0x1e, 0x13, 0x01, 0xb3, 0xd9, 0x3d, 
+  0x1f, 0x3d, 0x85, 0xd0, 0xd7, 0x45, 0xd0, 0xd7, 
+  0x53, 0xd2, 0xfd, 0x60, 0xab, 
+
+ /* Char 8364 is 23px wide @ 3557 */
+ /*                 ***    ***                 */ 
+ /*                 ***    ***                 */ 
+ /*                 ***    ***                 */ 
+ /*                ***********                 */ 
+ /*             *****************              */ 
+ /*            ********************            */ 
+ /*          ***********************           */ 
+ /*          **********    *********           */ 
+ /*         *****   ***    ***  *****          */ 
+ /*         ****    ***    ***    ***          */ 
+ /*        ****     ***    ***    ****         */ 
+ /*        ***      ***    ***     ***         */ 
+ /*        ***      ***    ***     ***         */ 
+ /*        ***      ***    ***     ***         */ 
+ /*        ***      ***    ***     ***         */ 
+ /*        ***             ***     ***         */ 
+ /*        ***                    ****         */ 
+ /*         ***                    **          */ 
+ /*         **                                 */ 
+  0x05, 0x8e, 0x13, 0x43, 0x01, 0x3b, 0xdf, 0xd4, 
+  0xdb, 0xd7, 0xd7, 0xda, 0xd6, 0xa4, 0x9d, 0x55, 
+  0x33, 0x43, 0x25, 0xd4, 0x44, 0x34, 0x34, 0x3d, 
+  0x34, 0x53, 0x43, 0x44, 0xd2, 0xe2, 0x36, 0x34, 
+  0x35, 0x3d, 0x23, 0xd0, 0x35, 0x3d, 0x23, 0xd7, 
+  0x4d, 0x33, 0xd7, 0x2d, 0x42, 0x06, 0x81, 
+
+};
+
+/* Character descriptors */
+const FONT_CHAR_INFO Ubuntu29ptLengths[] = {
+ { 3}, /*   */
+ {15}, /* ! */
+ {15}, /* " */
+ {56}, /* # */
+ {47}, /* $ */
+ {79}, /* % */
+ {66}, /* & */
+ { 8}, /* ' */
+ {24}, /* ( */
+ {24}, /* ) */
+ {41}, /* * */
+ {11}, /* + */
+ {12}, /* , */
+ { 5}, /* - */
+ { 9}, /* . */
+ {30}, /* / */
+ {44}, /* 0 */
+ {18}, /* 1 */
+ {53}, /* 2 */
+ {43}, /* 3 */
+ {34}, /* 4 */
+ {37}, /* 5 */
+ {50}, /* 6 */
+ {41}, /* 7 */
+ {56}, /* 8 */
+ {50}, /* 9 */
+ {12}, /* : */
+ {16}, /* ; */
+ {41}, /* < */
+ { 7}, /* = */
+ {41}, /* > */
+ {36}, /* ? */
+ {81}, /* @ */
+ {57}, /* A */
+ {38}, /* B */
+ {49}, /* C */
+ {40}, /* D */
+ {14}, /* E */
+ {11}, /* F */
+ {48}, /* G */
+ {11}, /* H */
+ { 5}, /* I */
+ {25}, /* J */
+ {50}, /* K */
+ { 8}, /* L */
+ {57}, /* M */
+ {37}, /* N */
+ {57}, /* O */
+ {32}, /* P */
+ {71}, /* Q */
+ {38}, /* R */
+ {56}, /* S */
+ {12}, /* T */
+ {37}, /* U */
+ {50}, /* V */
+ {69}, /* W */
+ {61}, /* X */
+ {47}, /* Y */
+ {66}, /* Z */
+ {10}, /* [ */
+ {32}, /* \ */
+ { 9}, /* ] */
+ {40}, /* ^ */
+ { 5}, /* _ */
+ {16}, /* ` */
+ {36}, /* a */
+ {33}, /* b */
+ {30}, /* c */
+ {36}, /* d */
+ {46}, /* e */
+ {23}, /* f */
+ {50}, /* g */
+ {23}, /* h */
+ { 6}, /* i */
+ {16}, /* j */
+ {33}, /* k */
+ {13}, /* l */
+ {38}, /* m */
+ {22}, /* n */
+ {37}, /* o */
+ {33}, /* p */
+ {33}, /* q */
+ {10}, /* r */
+ {31}, /* s */
+ {23}, /* t */
+ {22}, /* u */
+ {37}, /* v */
+ {59}, /* w */
+ {46}, /* x */
+ {47}, /* y */
+ {48}, /* z */
+ {28}, /* { */
+ { 6}, /* | */
+ {27}, /* } */
+ {35}, /* ~ */
+ {67}, /* Ä */
+ {64}, /* Ö */
+ {46}, /* Ü */
+ {52}, /* ß */
+ {48}, /* ä */
+ {53}, /* ö */
+ {37}, /* ü */
+ {47}, /* € */
+};
+
+const uint16_t Ubuntu29ptExtra[] = {
+196,214,220,223,228,246,252,8364,65535
+};
+
+/* Font info */
+const struct FONT_DEF Font_Ubuntu29pt = {
+         1,   /* width (1 == comressed) */
+        42,   /* character height */
+        32,   /* first char */
+       126,   /* last char */
+    Ubuntu29ptBitmaps, Ubuntu29ptLengths, Ubuntu29ptExtra
+};
+
+/* Font metadata: 
+ * Name:          Ubuntu Regular 29pt
+ * Height:        42 px (6 bytes)
+ * Maximum width: 38 px
+ * Storage size:  3707 bytes (compressed by 72%)
+ */
diff --git a/lcd/fonts/ubuntu29.h b/lcd/fonts/ubuntu29.h
new file mode 100644 (file)
index 0000000..7d3a059
--- /dev/null
@@ -0,0 +1,3 @@
+#include "lcd/fonts.h"
+
+extern const struct FONT_DEF Font_Ubuntu29pt;
diff --git a/lcd/fonts/ubuntu36.c b/lcd/fonts/ubuntu36.c
new file mode 100644 (file)
index 0000000..013a861
--- /dev/null
@@ -0,0 +1,3092 @@
+#include "ubuntu36.h"
+
+/* Font data for Ubuntu Regular 36pt */
+
+/* Copyright 2010 Canonical Ltd.  Licensed under the Ubuntu Font Licence 1.0
+ * 
+ */
+
+/* This file created by makefont.pl by Sec <sec@42.org> */
+
+/* Bitmaps */
+const uint8_t Ubuntu36ptBitmaps[] = {
+ /* Char 32 is 12px wide @ 0 */
+ /*                                                      */ 
+  0x00, 0x26, 0x41, 
+
+ /* Char 33 is 14px wide @ 3 */
+ /*            **                                        */ 
+ /*           ****          ******************           */ 
+ /*          ******     **********************           */ 
+ /*          ******     **********************           */ 
+ /*           ****          ******************           */ 
+ /*            **                                        */ 
+  0x09, 0xb2, 0x02, 0x54, 0xad, 0x5d, 0x6f, 0x65, 
+  0xd9, 0xd7, 0x4a, 0xd5, 0xd8, 0x20, 0x01, 0x1f, 
+
+
+ /* Char 34 is 21px wide @ 19 */
+ /*                                      **********      */ 
+ /*                                    ************      */ 
+ /*                                    ************      */ 
+ /*                                      **********      */ 
+ /*                                                      */ 
+ /*                                                      */ 
+ /*                                                      */ 
+ /*                                                      */ 
+ /*                                                      */ 
+ /*                                      **********      */ 
+ /*                                    ************      */ 
+ /*                                    ************      */ 
+ /*                                      **********      */ 
+  0x0e, 0x9a, 0x01, 0xcf, 0xc0, 0x1e, 0xa0, 0x01, 
+  0x22, 0xa0, 0x1c, 0xfc, 0x01, 0xea, 0x0c, 0x91, 
+
+
+ /* Char 35 is 33px wide @ 35 */
+ /*                   ****       ****                    */ 
+ /*                   ****       ****                    */ 
+ /*                   ****       ****                    */ 
+ /*          ***      ****       ****                    */ 
+ /*          *************       ****                    */ 
+ /*          **************      ****                    */ 
+ /*          ************************                    */ 
+ /*            ***********************                   */ 
+ /*                  ***********************             */ 
+ /*                   ************************           */ 
+ /*                   ****      **************           */ 
+ /*                   ****       *************           */ 
+ /*                   ****       ****      ***           */ 
+ /*                   ****       ****                    */ 
+ /*                   ****       ****                    */ 
+ /*          ***      ****       ****                    */ 
+ /*          *************       ****                    */ 
+ /*          **************      ****                    */ 
+ /*          ************************                    */ 
+ /*            ***********************                   */ 
+ /*                  ***********************             */ 
+ /*                   ************************           */ 
+ /*                   ****      **************           */ 
+ /*                   ****       *************           */ 
+ /*                   ****       ****      ***           */ 
+ /*                   ****       ****                    */ 
+ /*                   ****       ****                    */ 
+ /*                   ****       ****                    */ 
+  0x06, 0xee, 0x14, 0x74, 0xdf, 0x36, 0x47, 0x4d, 
+  0xfd, 0x07, 0x4d, 0xfd, 0x16, 0x4d, 0xfd, 0xb0, 
+  0x12, 0xda, 0x01, 0x7d, 0xa0, 0x12, 0xdb, 0xdf, 
+  0x46, 0xd1, 0xdf, 0x47, 0xd0, 0xdf, 0x47, 0x46, 
+  0x3d, 0xff, 0x47, 0x4d, 0xf3, 0x64, 0x74, 0xdf, 
+  0xd0, 0x74, 0xdf, 0xd1, 0x64, 0xdf, 0xdb, 0x01, 
+  0x2d, 0xa0, 0x17, 0xda, 0x01, 0x2d, 0xbd, 0xf4, 
+  0x6d, 0x1d, 0xf4, 0x7d, 0x0d, 0xf4, 0x74, 0x63, 
+  0xdf, 0xe1, 0x47, 0x40, 0xa3, 
+
+ /* Char 36 is 28px wide @ 104 */
+ /*            **                                        */ 
+ /*           *****               ******                 */ 
+ /*           ****              *********                */ 
+ /*           ****             ***********               */ 
+ /*          *****            *************              */ 
+ /*          *****            *****   ******             */ 
+ /*          ****            *****      ****             */ 
+ /*          ****            ****       ****             */ 
+ /*          ****           *****        ****            */ 
+ /*    **********           ****         *********       */ 
+ /*    **********          *****         *********       */ 
+ /*    **********          ****          *********       */ 
+ /*    **********         *****          *********       */ 
+ /*          ****         ****           ****            */ 
+ /*          *****       *****           ****            */ 
+ /*           ****      *****           *****            */ 
+ /*           ******  ******            *****            */ 
+ /*            *************            ****             */ 
+ /*            ************              ***             */ 
+ /*             *********                                */ 
+ /*               ******                                 */ 
+  0x09, 0xb2, 0x02, 0x55, 0xd2, 0x6d, 0xd4, 0xd1, 
+  0x9d, 0xc4, 0xd0, 0xbd, 0xa5, 0xcd, 0x0d, 0x95, 
+  0xc5, 0x36, 0xd8, 0x4c, 0x56, 0x4d, 0x84, 0xc4, 
+  0x74, 0xd8, 0x4b, 0x58, 0x4d, 0x1a, 0xb4, 0x99, 
+  0x9a, 0xa5, 0x99, 0x9a, 0xa4, 0xa9, 0x9a, 0x95, 
+  0xa9, 0xd2, 0x49, 0x4b, 0x4d, 0x75, 0x75, 0xb4, 
+  0xd8, 0x46, 0x5b, 0x5d, 0x86, 0x26, 0xc5, 0xd9, 
+  0xd0, 0xc4, 0xda, 0xcd, 0x13, 0xdb, 0x90, 0x21, 
+  0x60, 0xe4, 
+
+ /* Char 37 is 42px wide @ 170 */
+ /*                               *******                */ 
+ /*                             ***********              */ 
+ /*                            *************             */ 
+ /*                           ***************            */ 
+ /*                           *****     *****            */ 
+ /*                          ****         ****           */ 
+ /*                          ***           ***           */ 
+ /*          *               ***           ***           */ 
+ /*          ***             ***           ***           */ 
+ /*          *****           ***           ***           */ 
+ /*          ******          ****         ****           */ 
+ /*          ********         *****     *****            */ 
+ /*            ********       ***************            */ 
+ /*              ********      *************             */ 
+ /*               ********      ***********              */ 
+ /*                 ********      *******                */ 
+ /*                   ********                           */ 
+ /*                     ********                         */ 
+ /*                      *********                       */ 
+ /*                        ********                      */ 
+ /*                          ********                    */ 
+ /*               *******      ********                  */ 
+ /*             ***********      ********                */ 
+ /*            *************      ********               */ 
+ /*           ***************       ********             */ 
+ /*           *****     *****         ********           */ 
+ /*          ****         ****          ******           */ 
+ /*          ***           ***           *****           */ 
+ /*          ***           ***             ***           */ 
+ /*          ***           ***               *           */ 
+ /*          ***           ***                           */ 
+ /*          ****         ****                           */ 
+ /*           *****     *****                            */ 
+ /*           ***************                            */ 
+ /*            *************                             */ 
+ /*             ***********                              */ 
+ /*               *******                                */ 
+  0x07, 0xa7, 0x01, 0xfb, 0x01, 0xcd, 0x00, 0x1a, 
+  0xd2, 0x01, 0x95, 0x55, 0x01, 0x84, 0x94, 0x01, 
+  0x73, 0xb3, 0xd6, 0x1d, 0x23, 0xb3, 0xd6, 0x3d, 
+  0x03, 0xb3, 0xd6, 0x5b, 0x3b, 0x3d, 0x66, 0xa4, 
+  0x94, 0xd6, 0x89, 0x55, 0x5d, 0x98, 0x7d, 0x2d, 
+  0xb8, 0x6d, 0x0d, 0xd8, 0x6b, 0x01, 0x18, 0x67, 
+  0x01, 0x58, 0x02, 0x28, 0x02, 0x19, 0x02, 0x18, 
+  0x02, 0x28, 0x01, 0x57, 0x68, 0x01, 0x1b, 0x68, 
+  0xdd, 0xd0, 0x68, 0xdb, 0xd2, 0x78, 0xd9, 0x55, 
+  0x59, 0x8d, 0x64, 0x94, 0xa6, 0xd6, 0x3b, 0x3b, 
+  0x5d, 0x63, 0xb3, 0xd0, 0x3d, 0x63, 0xb3, 0xd2, 
+  0x1d, 0x63, 0xb3, 0x01, 0x74, 0x94, 0x01, 0x85, 
+  0x55, 0x01, 0x9d, 0x20, 0x1a, 0xd0, 0x01, 0xcb, 
+  0x01, 0xf7, 0x0a, 0xf1, 
+
+ /* Char 38 is 33px wide @ 278 */
+ /*                ******                                */ 
+ /*              **********                              */ 
+ /*             ************                             */ 
+ /*            **************                            */ 
+ /*            *****    ******     ******                */ 
+ /*           *****      *****   **********              */ 
+ /*           ****        ***** ************             */ 
+ /*          *****         ******************            */ 
+ /*          ****          *********    *****            */ 
+ /*          ****           ******       *****           */ 
+ /*          ****          ******         ****           */ 
+ /*          ****         ********        ****           */ 
+ /*          ****        *********        ****           */ 
+ /*          ****       ***********      *****           */ 
+ /*          *****     ******  *****     *****           */ 
+ /*           ****    ******   ******   *****            */ 
+ /*           ****   ******     *************            */ 
+ /*           ***** ******       ***********             */ 
+ /*            **********         *********              */ 
+ /*             ********            ******               */ 
+ /*              ******                                  */ 
+ /*             ********                                 */ 
+ /*            ***********                               */ 
+ /*           ***** ********                             */ 
+ /*          *****    *******                            */ 
+ /*          ****      ******                            */ 
+ /*          ****         ***                            */ 
+ /*          **                                          */ 
+ /*          *                                           */ 
+  0x06, 0xb6, 0x02, 0x0a, 0x01, 0xdc, 0x01, 0xbd, 
+  0x10, 0x1a, 0x54, 0x65, 0x6d, 0xc5, 0x65, 0x3a, 
+  0xda, 0x48, 0x51, 0xcd, 0x85, 0x9d, 0x5d, 0x74, 
+  0xa9, 0x45, 0xd7, 0x4b, 0x67, 0x5d, 0x64, 0xa6, 
+  0x94, 0xd6, 0x49, 0x88, 0x4d, 0x64, 0x89, 0x84, 
+  0xd6, 0x47, 0xb6, 0x5d, 0x65, 0x56, 0x25, 0x55, 
+  0xd7, 0x44, 0x63, 0x63, 0x5d, 0x84, 0x36, 0x5d, 
+  0x0d, 0x85, 0x16, 0x7b, 0xda, 0xa9, 0x9d, 0xc8, 
+  0xc6, 0xde, 0x60, 0x21, 0x80, 0x1f, 0xb0, 0x1c, 
+  0x51, 0x80, 0x19, 0x54, 0x70, 0x18, 0x46, 0x60, 
+  0x18, 0x49, 0x30, 0x18, 0x20, 0x26, 0x10, 0x86, 
+
+
+ /* Char 39 is 13px wide @ 366 */
+ /*                                      **********      */ 
+ /*                                    ************      */ 
+ /*                                    ************      */ 
+ /*                                      **********      */ 
+  0x0e, 0x9a, 0x01, 0xcf, 0xc0, 0x1e, 0xa0, 0xfd, 
+
+
+ /* Char 40 is 17px wide @ 374 */
+ /*                  *************                       */ 
+ /*              *********************                   */ 
+ /*           ***************************                */ 
+ /*         *******************************              */ 
+ /*      *************           *************           */ 
+ /*     *********                     *********          */ 
+ /*   ********                           ********        */ 
+ /*  *******                               *******       */ 
+ /* ******                                   ******      */ 
+ /*  ****                                     ****       */ 
+ /*   *                                         *        */ 
+  0x0d, 0x5d, 0x00, 0x17, 0xd8, 0xdf, 0xde, 0xda, 
+  0x01, 0x3d, 0x5d, 0x0b, 0xd0, 0xd1, 0x9d, 0x89, 
+  0xb8, 0xde, 0x88, 0x70, 0x13, 0x76, 0x60, 0x17, 
+  0x66, 0x40, 0x19, 0x48, 0x10, 0x1d, 0x10, 0x63, 
+
+
+ /* Char 41 is 17px wide @ 406 */
+ /*   *                                         *        */ 
+ /*  ****                                     ****       */ 
+ /* ******                                   ******      */ 
+ /*  *******                               *******       */ 
+ /*   ********                           ********        */ 
+ /*     *********                     *********          */ 
+ /*      *************           *************           */ 
+ /*         *******************************              */ 
+ /*           ***************************                */ 
+ /*              *********************                   */ 
+ /*                  *************                       */ 
+  0x02, 0xa1, 0x01, 0xd1, 0x84, 0x01, 0x94, 0x66, 
+  0x01, 0x76, 0x67, 0x01, 0x37, 0x88, 0xde, 0x8b, 
+  0x9d, 0x89, 0xd1, 0xd0, 0xbd, 0x0d, 0x50, 0x13, 
+  0xda, 0xde, 0xdf, 0xd8, 0x01, 0x7d, 0x00, 0x01, 
+  0x0e, 
+
+ /* Char 42 is 24px wide @ 439 */
+ /*                                    *                 */ 
+ /*                                   ****               */ 
+ /*                           *       ****               */ 
+ /*                          ***     ****                */ 
+ /*                          ****    ****                */ 
+ /*                         ******   ***                 */ 
+ /*                           *****  ***                 */ 
+ /*                            ********   ****           */ 
+ /*                              *************           */ 
+ /*                                ***********           */ 
+ /*                              *************           */ 
+ /*                            ********   ****           */ 
+ /*                           *****  ***                 */ 
+ /*                         ******   ***                 */ 
+ /*                          ****    ****                */ 
+ /*                          ***     ****                */ 
+ /*                           *       ****               */ 
+ /*                                   ****               */ 
+ /*                                    *                 */ 
+  0x07, 0xf1, 0x02, 0x64, 0x01, 0xc1, 0x74, 0x01, 
+  0xb3, 0x54, 0x01, 0xc4, 0x44, 0x01, 0xb6, 0x33, 
+  0x01, 0xe5, 0x23, 0x01, 0xf8, 0x34, 0x01, 0xbd, 
+  0x00, 0x1d, 0xb0, 0x1b, 0xd0, 0x01, 0x98, 0x34, 
+  0x01, 0x85, 0x23, 0x01, 0xc6, 0x33, 0x01, 0xd4, 
+  0x44, 0x01, 0xc3, 0x54, 0x01, 0xd1, 0x74, 0x02, 
+  0x44, 0x02, 0x51, 0x0a, 0x01, 
+
+ /* Char 43 is 28px wide @ 492 */
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*             **********************                   */ 
+ /*             **********************                   */ 
+ /*             **********************                   */ 
+ /*             **********************                   */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+  0x0a, 0x5e, 0x74, 0x01, 0xbe, 0x2d, 0x90, 0x1b, 
+  0xe7, 0x40, 0xab, 
+
+ /* Char 44 is 13px wide @ 503 */
+ /*   **                                                 */ 
+ /*  ******                                              */ 
+ /*  *************                                       */ 
+ /*    ***********                                       */ 
+ /*      *********                                       */ 
+ /*          *****                                       */ 
+  0x05, 0xe2, 0x02, 0x56, 0x02, 0x2d, 0x00, 0x1d, 
+  0xb0, 0x1f, 0x90, 0x23, 0x50, 0x01, 0x1e, 
+
+ /* Char 45 is 16px wide @ 518 */
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+ /*                      ***                             */ 
+  0x03, 0xde, 0xa3, 0x0a, 0xc1, 
+
+ /* Char 46 is 13px wide @ 523 */
+ /*            **                                        */ 
+ /*           ****                                       */ 
+ /*          ******                                      */ 
+ /*          ******                                      */ 
+ /*           ****                                       */ 
+ /*            **                                        */ 
+  0x09, 0xb2, 0x02, 0x54, 0x02, 0x3f, 0x60, 0x23, 
+  0x40, 0x25, 0x20, 0xeb, 
+
+ /* Char 47 is 20px wide @ 535 */
+ /* ****                                                 */ 
+ /* *******                                              */ 
+ /* **********                                           */ 
+ /*  ************                                        */ 
+ /*     ************                                     */ 
+ /*       ************                                   */ 
+ /*          ************                                */ 
+ /*             ************                             */ 
+ /*                ************                          */ 
+ /*                   ***********                        */ 
+ /*                     ************                     */ 
+ /*                        ************                  */ 
+ /*                           ************               */ 
+ /*                              ************            */ 
+ /*                                ************          */ 
+ /*                                   ************       */ 
+ /*                                      **********      */ 
+ /*                                         *******      */ 
+ /*                                            ****      */ 
+ /*                                              **      */ 
+  0xe4, 0x02, 0x47, 0x02, 0x1a, 0x01, 0xfc, 0x01, 
+  0xfc, 0x01, 0xec, 0x01, 0xfc, 0x01, 0xfc, 0x01, 
+  0xfc, 0x01, 0xfb, 0x01, 0xfc, 0x01, 0xfc, 0x01, 
+  0xfc, 0x01, 0xfc, 0x01, 0xec, 0x01, 0xfc, 0x01, 
+  0xfa, 0x02, 0x17, 0x02, 0x44, 0x02, 0x62, 0x51, 
+
+
+ /* Char 48 is 28px wide @ 575 */
+ /*                     ***********                      */ 
+ /*                  *****************                   */ 
+ /*               ***********************                */ 
+ /*              *************************               */ 
+ /*             ********           ********              */ 
+ /*            ******                 ******             */ 
+ /*           ******                   ******            */ 
+ /*           *****                     *****            */ 
+ /*          *****                       *****           */ 
+ /*          *****                        ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          *****                        ****           */ 
+ /*          *****                       *****           */ 
+ /*           *****                     *****            */ 
+ /*           ******                   ******            */ 
+ /*            ******                 ******             */ 
+ /*             *********         *********              */ 
+ /*              *************************               */ 
+ /*               ***********************                */ 
+ /*                  *****************                   */ 
+ /*                     ***********                      */ 
+  0x07, 0x0b, 0x01, 0xad, 0x40, 0x14, 0xda, 0xdf, 
+  0xdc, 0xdd, 0x8b, 0x8d, 0xb6, 0xd4, 0x6d, 0x96, 
+  0xd6, 0x6d, 0x85, 0xd8, 0x5d, 0x75, 0xda, 0x5d, 
+  0x65, 0xdb, 0x4d, 0x6e, 0x14, 0xdc, 0x4d, 0x65, 
+  0xdb, 0x4d, 0x65, 0xda, 0x5d, 0x75, 0xd8, 0x5d, 
+  0x86, 0xd6, 0x6d, 0x96, 0xd4, 0x6d, 0xb9, 0x99, 
+  0xdd, 0xdc, 0xdf, 0xda, 0x01, 0x4d, 0x40, 0x1a, 
+  0xb0, 0xa5, 
+
+ /* Char 49 is 28px wide @ 633 */
+ /*                                   **                 */ 
+ /*                                 *****                */ 
+ /*                                 *****                */ 
+ /*                                  *****               */ 
+ /*                                  *****               */ 
+ /*                                   *****              */ 
+ /*                                   *****              */ 
+ /*                                    *****             */ 
+ /*                                     *****            */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+  0x0e, 0x62, 0x02, 0x4f, 0x50, 0x24, 0xf5, 0x02, 
+  0x4f, 0x50, 0x24, 0x50, 0x24, 0x5d, 0x7e, 0x20, 
+  0x15, 0x00, 0x23, 0xa1, 
+
+ /* Char 50 is 28px wide @ 653 */
+ /*                                      **              */ 
+ /*          ****                       ***              */ 
+ /*          ******                    *****             */ 
+ /*          ********                   *****            */ 
+ /*          *********                  *****            */ 
+ /*          **** ******                 ****            */ 
+ /*          ****  ******                *****           */ 
+ /*          ****   ******                ****           */ 
+ /*          ****    ******               ****           */ 
+ /*          ****     ******              ****           */ 
+ /*          ****      ******             ****           */ 
+ /*          ****       ******            ****           */ 
+ /*          ****        ******           ****           */ 
+ /*          ****         ******         *****           */ 
+ /*          ****          ******       *****            */ 
+ /*          ****           *******    ******            */ 
+ /*          ****            ***************             */ 
+ /*          ****              ************              */ 
+ /*          ****               **********               */ 
+ /*          ****                 ******                 */ 
+ /*          ****                                        */ 
+  0x08, 0x12, 0xd9, 0x4d, 0xa3, 0xd9, 0x6d, 0x75, 
+  0xd8, 0x8d, 0x65, 0xd7, 0x9d, 0x55, 0xd7, 0x41, 
+  0x6d, 0x44, 0xd7, 0x42, 0x6d, 0x35, 0xd6, 0x43, 
+  0x6d, 0x34, 0xd6, 0x44, 0x6d, 0x24, 0xd6, 0x45, 
+  0x6d, 0x14, 0xd6, 0x46, 0x6d, 0x04, 0xd6, 0x47, 
+  0x6c, 0x4d, 0x64, 0x86, 0xb4, 0xd6, 0x49, 0x69, 
+  0x5d, 0x64, 0xa6, 0x75, 0xd7, 0x4b, 0x74, 0x6d, 
+  0x74, 0xcd, 0x2d, 0x84, 0xd1, 0xcd, 0x94, 0xd2, 
+  0xad, 0xa4, 0xd4, 0x6d, 0xc4, 0x00, 0x11, 0xf1, 
+
+
+ /* Char 51 is 28px wide @ 725 */
+ /*           ***                                        */ 
+ /*           ****                        **             */ 
+ /*           ****                      ****             */ 
+ /*           ****                      *****            */ 
+ /*          *****                       ****            */ 
+ /*          ****                        ****            */ 
+ /*          ****            ****        *****           */ 
+ /*          ****            ****         ****           */ 
+ /*          ****            ****         ****           */ 
+ /*          ****            ****         ****           */ 
+ /*          ****            ****         ****           */ 
+ /*          ****           ******        ****           */ 
+ /*           ****          ******       *****           */ 
+ /*           ****         ********      ****            */ 
+ /*           *****       ***** ****   ******            */ 
+ /*            ******    ******  ***********             */ 
+ /*            ***************   ***********             */ 
+ /*             *************     *********              */ 
+ /*               **********        *****                */ 
+ /*                 ******                               */ 
+  0x09, 0xa3, 0x02, 0x54, 0xdb, 0x2d, 0x94, 0xd9, 
+  0x4d, 0x94, 0xd9, 0x5d, 0x75, 0xda, 0x4d, 0x74, 
+  0xdb, 0x4d, 0x74, 0xc4, 0x85, 0xd6, 0xe2, 0x4c, 
+  0x49, 0x4d, 0x64, 0xb6, 0x84, 0xd7, 0x4a, 0x67, 
+  0x5d, 0x74, 0x98, 0x64, 0xd8, 0x57, 0x51, 0x43, 
+  0x6d, 0x96, 0x46, 0x2b, 0xda, 0xd2, 0x3b, 0xdb, 
+  0xd0, 0x59, 0xde, 0xa8, 0x50, 0x13, 0x60, 0x01, 
+  0x16, 
+
+ /* Char 52 is 28px wide @ 782 */
+ /*                  ****                                */ 
+ /*                  ******                              */ 
+ /*                  ********                            */ 
+ /*                  **********                          */ 
+ /*                  ************                        */ 
+ /*                  **** ********                       */ 
+ /*                  ****   ********                     */ 
+ /*                  ****    ********                    */ 
+ /*                  ****      *******                   */ 
+ /*                  ****        *******                 */ 
+ /*                  ****         *******                */ 
+ /*                  ****          *******               */ 
+ /*                  ****            ******              */ 
+ /*                  ****             ******             */ 
+ /*                  ****              *******           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                  ****                                */ 
+ /*                  ****                                */ 
+ /*                  ****                                */ 
+ /*                  ****                                */ 
+  0x06, 0xd4, 0x02, 0x46, 0x02, 0x28, 0x02, 0x0a, 
+  0x01, 0xec, 0x01, 0xc4, 0x18, 0x01, 0xb4, 0x38, 
+  0x01, 0x94, 0x48, 0x01, 0x84, 0x67, 0x01, 0x74, 
+  0x87, 0x01, 0x54, 0x97, 0x01, 0x44, 0xa7, 0x01, 
+  0x34, 0xc6, 0x01, 0x24, 0xd0, 0x60, 0x11, 0x4d, 
+  0x17, 0xd6, 0xe2, 0x01, 0x5d, 0xee, 0x24, 0x0a, 
+  0xf1, 
+
+ /* Char 53 is 28px wide @ 831 */
+ /*           ***                                        */ 
+ /*           ****                                       */ 
+ /*           ****            ********                   */ 
+ /*           ****            ****************           */ 
+ /*          *****            ****************           */ 
+ /*          ****             ****************           */ 
+ /*          ****             ****    ********           */ 
+ /*          ****             ****        ****           */ 
+ /*          ****            *****        ****           */ 
+ /*          ****            *****        ****           */ 
+ /*          ****            ****         ****           */ 
+ /*          ****            ****         ****           */ 
+ /*           ****          *****         ****           */ 
+ /*           ****          *****         ****           */ 
+ /*           *****        *****          ****           */ 
+ /*            ******    *******          ****           */ 
+ /*            ****************           ****           */ 
+ /*             **************            ****           */ 
+ /*               **********              ****           */ 
+ /*                 ******                               */ 
+  0x09, 0xa3, 0x02, 0x54, 0x02, 0x44, 0xc8, 0xdf, 
+  0x4c, 0xd3, 0xd6, 0x5c, 0xd3, 0xd6, 0x4d, 0x0d, 
+  0x3d, 0x64, 0xd0, 0x44, 0x8d, 0x64, 0xd0, 0x48, 
+  0x4d, 0x6f, 0x4c, 0x58, 0x4d, 0x6f, 0x4c, 0x49, 
+  0x4d, 0x7f, 0x4a, 0x59, 0x4d, 0x75, 0x85, 0xa4, 
+  0xd8, 0x64, 0x7a, 0x4d, 0x8d, 0x3b, 0x4d, 0x9d, 
+  0x1c, 0x4d, 0xba, 0xd1, 0x4d, 0xd6, 0x00, 0x11, 
+  0x61, 
+
+ /* Char 54 is 28px wide @ 888 */
+ /*                   **********                         */ 
+ /*                ****************                      */ 
+ /*              ********************                    */ 
+ /*             ***********************                  */ 
+ /*            ********      ***********                 */ 
+ /*            *****         ****  ******                */ 
+ /*           *****          ****    *****               */ 
+ /*           ****            ****    *****              */ 
+ /*          *****            ****     ****              */ 
+ /*          ****             ****     *****             */ 
+ /*          ****             ****      ****             */ 
+ /*          ****             ****      *****            */ 
+ /*          ****             ****       ****            */ 
+ /*          *****            ****       ****            */ 
+ /*           ****           ****        ****            */ 
+ /*           *****          ****        *****           */ 
+ /*           *****         *****         ****           */ 
+ /*            ******     ******          ****           */ 
+ /*             ****************          ****           */ 
+ /*              **************           ****           */ 
+ /*               ***********                            */ 
+ /*                  ******                              */ 
+  0x0a, 0x2a, 0x01, 0xbd, 0x30, 0x16, 0xd7, 0x01, 
+  0x3d, 0xad, 0xf8, 0x6b, 0xde, 0x59, 0x42, 0x6d, 
+  0xc5, 0xa4, 0x45, 0xdb, 0x4c, 0x44, 0x5d, 0x95, 
+  0xc4, 0x54, 0xd9, 0x4d, 0x04, 0x55, 0xd8, 0x4d, 
+  0x04, 0x64, 0xd8, 0x4d, 0x04, 0x65, 0xd7, 0x4d, 
+  0x04, 0x74, 0xd7, 0x5c, 0x47, 0x4d, 0x84, 0xb4, 
+  0x84, 0xd8, 0x5a, 0x48, 0x5d, 0x75, 0x95, 0x94, 
+  0xd8, 0x65, 0x6a, 0x4d, 0x9d, 0x3a, 0x4d, 0xad, 
+  0x1b, 0x4d, 0xbb, 0x02, 0x06, 0x0a, 0xd1, 
+
+ /* Char 55 is 28px wide @ 959 */
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*          ***                          ****           */ 
+ /*          ********                     ****           */ 
+ /*          ***********                  ****           */ 
+ /*          **************               ****           */ 
+ /*            ***************            ****           */ 
+ /*                  ***********          ****           */ 
+ /*                     **********        ****           */ 
+ /*                        *********      ****           */ 
+ /*                           *******     ****           */ 
+ /*                             *******   ****           */ 
+ /*                               ******  ****           */ 
+ /*                                ****** ****           */ 
+ /*                                  *********           */ 
+ /*                                    *******           */ 
+ /*                                     ******           */ 
+ /*                                      *****           */ 
+  0x0b, 0x6e, 0x34, 0xd6, 0x3d, 0xd4, 0xd6, 0x8d, 
+  0x84, 0xd6, 0xbd, 0x54, 0xd6, 0xd1, 0xd2, 0x4d, 
+  0x8d, 0x2c, 0x4d, 0xeb, 0xa4, 0x01, 0x2a, 0x84, 
+  0x01, 0x59, 0x64, 0x01, 0x87, 0x54, 0x01, 0xa7, 
+  0x34, 0x01, 0xc6, 0x24, 0x01, 0xd6, 0x14, 0x01, 
+  0xf9, 0x02, 0x17, 0x02, 0x26, 0x02, 0x35, 0x0c, 
+  0xe1, 
+
+ /* Char 56 is 28px wide @ 1008 */
+ /*                *****                                 */ 
+ /*              *********         *****                 */ 
+ /*             ***********     **********               */ 
+ /*            *************   ************              */ 
+ /*           ******    ***** **************             */ 
+ /*           *****       *********    ******            */ 
+ /*           ****        ********       ****            */ 
+ /*          *****         ******        *****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****          *****          ****           */ 
+ /*          ****          ****           ****           */ 
+ /*          ****          ****           ****           */ 
+ /*          ****         ******          ****           */ 
+ /*          *****        *******        *****           */ 
+ /*           ****       ********       *****            */ 
+ /*           *****     ***** *****    ******            */ 
+ /*           ******   ******  *************             */ 
+ /*            *************    ***********              */ 
+ /*             ***********      *********               */ 
+ /*              *********         *****                 */ 
+ /*                *****                                 */ 
+  0x09, 0xf5, 0x02, 0x19, 0x95, 0xdf, 0xb5, 0xad, 
+  0xcd, 0x03, 0xcd, 0xa6, 0x45, 0x1d, 0x1d, 0x95, 
+  0x79, 0x46, 0xd8, 0x48, 0x87, 0x4d, 0x75, 0x96, 
+  0x85, 0xd6, 0x4b, 0x4a, 0x4d, 0x64, 0xa5, 0xa4, 
+  0xd6, 0xf4, 0xa4, 0xb4, 0xd6, 0x49, 0x6a, 0x4d, 
+  0x65, 0x87, 0x85, 0xd7, 0x47, 0x87, 0x5d, 0x85, 
+  0x55, 0x15, 0x46, 0xd8, 0x63, 0x62, 0xd0, 0xda, 
+  0xd0, 0x4b, 0xdc, 0xb6, 0x9d, 0xe9, 0x95, 0x01, 
+  0x35, 0x0e, 0x41, 
+
+ /* Char 57 is 28px wide @ 1075 */
+ /*                             *******                  */ 
+ /*                           ***********                */ 
+ /*          ****            *************               */ 
+ /*          ****           ***************              */ 
+ /*          ****           ******    ******             */ 
+ /*          ****          *****        *****            */ 
+ /*          ****          ****          ****            */ 
+ /*          *****        *****          ****            */ 
+ /*           ****        ****            ****           */ 
+ /*           ****        ****            ****           */ 
+ /*           *****       ****            ****           */ 
+ /*            ****       ****            ****           */ 
+ /*            *****      ****            ****           */ 
+ /*            ******     ****           *****           */ 
+ /*             ******    ****           ****            */ 
+ /*              ******    ****         *****            */ 
+ /*               *******  ****        *****             */ 
+ /*                ************      *******             */ 
+ /*                 ***********************              */ 
+ /*                  *********************               */ 
+ /*                    *****************                 */ 
+ /*                        **********                    */ 
+  0x07, 0x87, 0x01, 0xfb, 0xdb, 0x4c, 0xd0, 0xda, 
+  0x4b, 0xd2, 0xd9, 0x4b, 0x64, 0x6d, 0x84, 0xa5, 
+  0x85, 0xd7, 0x4a, 0x4a, 0x4d, 0x75, 0x85, 0xa4, 
+  0xd8, 0xf4, 0x84, 0xc4, 0xd7, 0x57, 0x4c, 0x4d, 
+  0x84, 0x74, 0xc4, 0xd8, 0x56, 0x4c, 0x4d, 0x86, 
+  0x54, 0xb5, 0xd9, 0x64, 0x4b, 0x4d, 0xb6, 0x44, 
+  0x95, 0xdc, 0x72, 0x48, 0x5d, 0xec, 0x67, 0xdf, 
+  0xda, 0x01, 0x2d, 0x80, 0x15, 0xd4, 0x01, 0xba, 
+  0x0d, 0x71, 
+
+ /* Char 58 is 13px wide @ 1141 */
+ /*            **                 **                     */ 
+ /*           ****               ****                    */ 
+ /*          ******             ******                   */ 
+ /*          ******             ******                   */ 
+ /*           ****               ****                    */ 
+ /*            **                 **                     */ 
+  0x09, 0xb2, 0xd4, 0x20, 0x12, 0x4d, 0x24, 0xdf, 
+  0xf6, 0xd0, 0x6d, 0xf4, 0xd2, 0x40, 0x12, 0x2d, 
+  0x42, 0x0d, 0x81, 
+
+ /* Char 59 is 13px wide @ 1160 */
+ /*   **                                                 */ 
+ /*  ******                       **                     */ 
+ /*  *************               ****                    */ 
+ /*    ***********              ******                   */ 
+ /*      *********              ******                   */ 
+ /*          *****               ****                    */ 
+ /*                               **                     */ 
+  0x05, 0xe2, 0x02, 0x56, 0xda, 0x2d, 0x8d, 0x0d, 
+  0x24, 0xd9, 0xbd, 0x16, 0xda, 0x9d, 0x16, 0xde, 
+  0x5d, 0x24, 0x02, 0x52, 0x0d, 0x81, 
+
+ /* Char 60 is 28px wide @ 1182 */
+ /*                      *****                           */ 
+ /*                      *****                           */ 
+ /*                     *******                          */ 
+ /*                     *******                          */ 
+ /*                    *********                         */ 
+ /*                    *********                         */ 
+ /*                    **** ****                         */ 
+ /*                   ***** *****                        */ 
+ /*                   ****   ****                        */ 
+ /*                  *****   *****                       */ 
+ /*                  ****     ****                       */ 
+ /*                  ****     ****                       */ 
+ /*                 *****     *****                      */ 
+ /*                 ****       ****                      */ 
+ /*                *****       *****                     */ 
+ /*                ****         ****                     */ 
+ /*                ****         ****                     */ 
+ /*               *****         *****                    */ 
+ /*               ****           ****                    */ 
+ /*               ****           ****                    */ 
+ /*              ****             ****                   */ 
+ /*               ***             ***                    */ 
+  0x07, 0x1f, 0x50, 0x22, 0xf7, 0x02, 0x0f, 0x90, 
+  0x1f, 0x41, 0x40, 0x1e, 0x51, 0x50, 0x1d, 0x43, 
+  0x40, 0x1c, 0x53, 0x50, 0x1b, 0xf4, 0x54, 0x01, 
+  0xa5, 0x55, 0x01, 0x94, 0x74, 0x01, 0x85, 0x75, 
+  0x01, 0x7f, 0x49, 0x40, 0x16, 0x59, 0x50, 0x15, 
+  0xf4, 0xb4, 0x01, 0x44, 0xd0, 0x40, 0x14, 0x3d, 
+  0x03, 0x0d, 0x71, 
+
+ /* Char 61 is 28px wide @ 1233 */
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+ /*                  ****      ****                      */ 
+  0x06, 0xde, 0x01, 0x44, 0x64, 0x0d, 0x91, 
+
+ /* Char 62 is 28px wide @ 1240 */
+ /*               ***             ***                    */ 
+ /*              ****             ****                   */ 
+ /*               ****           ****                    */ 
+ /*               ****           ****                    */ 
+ /*               *****         *****                    */ 
+ /*                ****         ****                     */ 
+ /*                ****         ****                     */ 
+ /*                *****       ****                      */ 
+ /*                 ****       ****                      */ 
+ /*                 *****     *****                      */ 
+ /*                  ****     ****                       */ 
+ /*                  ****     ****                       */ 
+ /*                  *****   *****                       */ 
+ /*                   ****   ****                        */ 
+ /*                   ***** *****                        */ 
+ /*                    **** ****                         */ 
+ /*                    *********                         */ 
+ /*                    *********                         */ 
+ /*                     *******                          */ 
+ /*                     *******                          */ 
+ /*                      *****                           */ 
+ /*                      *****                           */ 
+  0x09, 0xe3, 0xd0, 0x30, 0x14, 0x4d, 0x04, 0x01, 
+  0x4f, 0x4b, 0x40, 0x15, 0x59, 0x50, 0x16, 0xf4, 
+  0x94, 0x01, 0x75, 0x74, 0x01, 0x94, 0x74, 0x01, 
+  0x95, 0x55, 0x01, 0xaf, 0x45, 0x40, 0x1b, 0x53, 
+  0x50, 0x1c, 0x43, 0x40, 0x1d, 0x51, 0x50, 0x1e, 
+  0x41, 0x40, 0x1f, 0xf9, 0x02, 0x0f, 0x70, 0x22, 
+  0xf5, 0x0a, 0xa1, 
+
+ /* Char 63 is 21px wide @ 1291 */
+ /*                                       **             */ 
+ /*                                      ****            */ 
+ /*                                      ****            */ 
+ /*                                      ****            */ 
+ /*                                       ****           */ 
+ /*           ****      ****              ****           */ 
+ /*          ******     ******            ****           */ 
+ /*          ******     *******           ****           */ 
+ /*           ****      ********          ****           */ 
+ /*                        ******         ****           */ 
+ /*                          *****       *****           */ 
+ /*                           *****      ****            */ 
+ /*                            *****    *****            */ 
+ /*                             *************            */ 
+ /*                              ***********             */ 
+ /*                               *********              */ 
+ /*                                 *****                */ 
+  0x04, 0xe2, 0x02, 0x5e, 0x14, 0x02, 0x54, 0xd7, 
+  0x46, 0x4d, 0x14, 0xd6, 0x65, 0x6c, 0x4d, 0x66, 
+  0x57, 0xb4, 0xd7, 0x46, 0x8a, 0x40, 0x15, 0x69, 
+  0x40, 0x17, 0x57, 0x50, 0x18, 0x56, 0x40, 0x1a, 
+  0x54, 0x50, 0x1b, 0xd0, 0x01, 0xcb, 0x01, 0xe9, 
+  0x02, 0x15, 0x09, 0xf1, 
+
+ /* Char 64 is 47px wide @ 1335 */
+ /*                 ***********                          */ 
+ /*              ******************                      */ 
+ /*            **********************                    */ 
+ /*          **************************                  */ 
+ /*         **********        **********                 */ 
+ /*        *******                *******                */ 
+ /*       ******                   *******               */ 
+ /*      ******                      ******              */ 
+ /*     ******                        ******             */ 
+ /*     *****                          *****             */ 
+ /*    *****           ******           *****            */ 
+ /*    ****         ************        *****            */ 
+ /*   *****        **************        *****           */ 
+ /*   *****      *****************        ****           */ 
+ /*   ****       ******     *******       ****           */ 
+ /*   ****      ******        ******      *****          */ 
+ /*  *****      *****          *****       ****          */ 
+ /*  ****      *****            ****       ****          */ 
+ /*  ****      ****             *****      ****          */ 
+ /*  ****      ****              ****      ****          */ 
+ /*  ****      ****              ****      ****          */ 
+ /*  ****      ****              ****      ****          */ 
+ /*  ****      ****              ****      ****          */ 
+ /*  ****      ****              ****      ****          */ 
+ /*  ****       ****             ****     *****          */ 
+ /*  ****       *********************     ****           */ 
+ /*  ****       ********************      ****           */ 
+ /*   ****      ********************     *****           */ 
+ /*   ****     *********************     *****           */ 
+ /*            *****                    *****            */ 
+ /*            ****                     *****            */ 
+ /*            ****                    *****             */ 
+ /*            *****                  *****              */ 
+ /*            *****                *******              */ 
+ /*             ******             *******               */ 
+ /*              ********       *********                */ 
+ /*               *********************                  */ 
+ /*                *******************                   */ 
+ /*                  ***************                     */ 
+ /*                     *********                        */ 
+  0x0a, 0x0b, 0x01, 0xad, 0x50, 0x14, 0xd9, 0xdf, 
+  0xdd, 0xdc, 0xa8, 0xad, 0xa7, 0xd3, 0x7d, 0x86, 
+  0xd6, 0x7d, 0x66, 0xd9, 0x6d, 0x46, 0xdb, 0x6d, 
+  0x35, 0xdd, 0x5d, 0x25, 0xb6, 0xb5, 0xd1, 0x49, 
+  0xc8, 0x5d, 0x05, 0x8d, 0x18, 0x5c, 0x56, 0xd4, 
+  0x84, 0xc4, 0x76, 0x57, 0x74, 0xc4, 0x66, 0x86, 
+  0x65, 0xa5, 0x65, 0xa5, 0x74, 0xa4, 0x65, 0xc4, 
+  0x74, 0xa4, 0x64, 0xd0, 0x56, 0x4a, 0xe3, 0x46, 
+  0x4d, 0x14, 0x64, 0xa4, 0x74, 0xd0, 0x45, 0x5a, 
+  0x47, 0xd8, 0x54, 0xb4, 0x7d, 0x76, 0x4c, 0x46, 
+  0xd7, 0x55, 0xc4, 0x5d, 0x85, 0x5d, 0x85, 0xd7, 
+  0x5d, 0x94, 0xd8, 0x5d, 0x94, 0xd7, 0x5d, 0xa5, 
+  0xd5, 0x5d, 0xb5, 0xd3, 0x7d, 0xc6, 0xd0, 0x7d, 
+  0xe8, 0x79, 0x01, 0x1d, 0x80, 0x14, 0xd6, 0x01, 
+  0x7d, 0x20, 0x1c, 0x90, 0xdb, 
+
+ /* Char 65 is 33px wide @ 1452 */
+ /*          *                                           */ 
+ /*          ****                                        */ 
+ /*          ******                                      */ 
+ /*          *********                                   */ 
+ /*          ***********                                 */ 
+ /*             ***********                              */ 
+ /*               ***********                            */ 
+ /*                  ***********                         */ 
+ /*                  *************                       */ 
+ /*                  **** ***********                    */ 
+ /*                  ****   ***********                  */ 
+ /*                  ****      ***********               */ 
+ /*                  ****        ***********             */ 
+ /*                  ****           **********           */ 
+ /*                  ****             ********           */ 
+ /*                  ****               ******           */ 
+ /*                  ****              *******           */ 
+ /*                  ****           **********           */ 
+ /*                  ****         **********             */ 
+ /*                  ****       **********               */ 
+ /*                  ****    **********                  */ 
+ /*                  ****  **********                    */ 
+ /*                  **************                      */ 
+ /*                  ************                        */ 
+ /*                 **********                           */ 
+ /*               **********                             */ 
+ /*             **********                               */ 
+ /*          **********                                  */ 
+ /*          ********                                    */ 
+ /*          ******                                      */ 
+ /*          ****                                        */ 
+ /*          *                                           */ 
+  0x91, 0x02, 0x74, 0x02, 0x46, 0x02, 0x29, 0x01, 
+  0xfb, 0x02, 0x0b, 0x01, 0xfb, 0x02, 0x0b, 0x01, 
+  0xdd, 0x00, 0x1b, 0x41, 0xb0, 0x18, 0x43, 0xb0, 
+  0x16, 0x46, 0xb0, 0x13, 0x48, 0xb0, 0x11, 0x4b, 
+  0xad, 0xe4, 0xd0, 0x8d, 0xe4, 0xd2, 0x6d, 0xe4, 
+  0xd1, 0x7d, 0xe4, 0xba, 0xde, 0x49, 0xa0, 0x11, 
+  0x47, 0xa0, 0x13, 0x44, 0xa0, 0x16, 0x42, 0xa0, 
+  0x18, 0xd1, 0x01, 0xac, 0x01, 0xba, 0x01, 0xca, 
+  0x01, 0xca, 0x01, 0xba, 0x01, 0xe8, 0x02, 0x06, 
+  0x02, 0x24, 0x02, 0x41, 0x05, 0x21, 
+
+ /* Char 66 is 32px wide @ 1530 */
+ /*           *******************************            */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           *****        *****           */ 
+ /*          *****          *****        ****            */ 
+ /*           ****         ******        ****            */ 
+ /*           ****         *******      *****            */ 
+ /*           *****        *********  ******             */ 
+ /*            *****      **** *************             */ 
+ /*            ******   ******  ***********              */ 
+ /*             *************    *********               */ 
+ /*              ***********      ******                 */ 
+ /*               *********                              */ 
+ /*                 ******                               */ 
+  0x0c, 0xe0, 0x13, 0xd7, 0xe1, 0x01, 0x5d, 0x6e, 
+  0x84, 0xb4, 0xa4, 0xd6, 0x4b, 0x58, 0x5d, 0x65, 
+  0xa5, 0x84, 0xd8, 0x49, 0x68, 0x4d, 0x84, 0x97, 
+  0x65, 0xd8, 0x58, 0x92, 0x6d, 0xa5, 0x64, 0x1d, 
+  0x0d, 0xa6, 0x36, 0x2b, 0xdc, 0xd0, 0x49, 0xde, 
+  0xb6, 0x60, 0x12, 0x90, 0x21, 0x60, 0xae, 
+
+ /* Char 67 is 31px wide @ 1577 */
+ /*                      *********                       */ 
+ /*                   ***************                    */ 
+ /*                 ******************                   */ 
+ /*                *********************                 */ 
+ /*              *********      *********                */ 
+ /*             *******             ******               */ 
+ /*             *****                ******              */ 
+ /*            *****                   ****              */ 
+ /*            ****                    *****             */ 
+ /*           *****                     *****            */ 
+ /*           ****                       ****            */ 
+ /*          *****                       ****            */ 
+ /*          *****                       *****           */ 
+ /*          ****                        *****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          *****                       *****           */ 
+ /*           ****                       ****            */ 
+ /*           ****                       ****            */ 
+ /*           ****                      *****            */ 
+ /*           *****                     ****             */ 
+ /*            **                         **             */ 
+  0x0a, 0x59, 0x01, 0xcd, 0x20, 0x17, 0xd5, 0x01, 
+  0x5d, 0x80, 0x11, 0x96, 0x9d, 0xe7, 0xd0, 0x6d, 
+  0xd5, 0xd3, 0x6d, 0xb5, 0xd6, 0x4d, 0xb4, 0xd7, 
+  0x5d, 0x95, 0xd8, 0x5d, 0x84, 0xda, 0x4d, 0x75, 
+  0xda, 0x4d, 0x75, 0xda, 0x5d, 0x64, 0xdb, 0x5d, 
+  0x6e, 0x44, 0xdc, 0x4d, 0x65, 0xda, 0x5d, 0x7f, 
+  0x4d, 0xa4, 0xd8, 0x4d, 0x95, 0xd8, 0x5d, 0x84, 
+  0xda, 0x2d, 0xc2, 0x06, 0x81, 
+
+ /* Char 68 is 35px wide @ 1638 */
+ /*           *******************************            */ 
+ /*           *******************************            */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          *****                       *****           */ 
+ /*           ****                       *****           */ 
+ /*           ****                       ****            */ 
+ /*           ****                       ****            */ 
+ /*           *****                     *****            */ 
+ /*           *****                     ****             */ 
+ /*            *****                   *****             */ 
+ /*            *****                   *****             */ 
+ /*             ******               ******              */ 
+ /*              ******             ******               */ 
+ /*               *********     *********                */ 
+ /*                *********************                 */ 
+ /*                 *******************                  */ 
+ /*                   ***************                    */ 
+ /*                      *********                       */ 
+  0x0c, 0xef, 0x01, 0x3d, 0x7f, 0x01, 0x5d, 0x6e, 
+  0x64, 0xdc, 0x4d, 0x65, 0xda, 0x5d, 0x74, 0xda, 
+  0x5d, 0x7f, 0x4d, 0xa4, 0xd8, 0x5d, 0x85, 0xd8, 
+  0x5d, 0x84, 0xda, 0xf5, 0xd6, 0x5d, 0xb6, 0xd2, 
+  0x6d, 0xd6, 0xd0, 0x6d, 0xf9, 0x59, 0x01, 0x2d, 
+  0x80, 0x14, 0xd6, 0x01, 0x7d, 0x20, 0x1c, 0x90, 
+  0xda, 
+
+ /* Char 69 is 29px wide @ 1687 */
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                                        */ 
+  0x0c, 0xde, 0x20, 0x15, 0xd6, 0xec, 0x4b, 0x4a, 
+  0x4d, 0x6f, 0x4d, 0xc4, 0xd6, 0x40, 0xeb, 
+
+ /* Char 70 is 27px wide @ 1702 */
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                         ****          ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+  0x0c, 0xde, 0x20, 0x15, 0x01, 0x6e, 0xc4, 0xa4, 
+  0x02, 0x4f, 0x40, 0x9a, 
+
+ /* Char 71 is 33px wide @ 1714 */
+ /*                     **********                       */ 
+ /*                   ***************                    */ 
+ /*                 *******************                  */ 
+ /*               **********************                 */ 
+ /*              *********      **********               */ 
+ /*             *******             *******              */ 
+ /*             *****                 *****              */ 
+ /*            *****                   *****             */ 
+ /*           *****                     *****            */ 
+ /*           *****                     *****            */ 
+ /*           ****                       ****            */ 
+ /*          *****                       *****           */ 
+ /*          *****                       *****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                        *****           */ 
+ /*          *****                       ****            */ 
+ /*           ***************            ****            */ 
+ /*           ***************           *****            */ 
+ /*           ***************           *****            */ 
+ /*           ***************             **             */ 
+  0x0a, 0x4a, 0x01, 0xcd, 0x20, 0x17, 0xd6, 0x01, 
+  0x3d, 0x90, 0x11, 0x96, 0xad, 0xd7, 0xd0, 0x7d, 
+  0xc5, 0xd4, 0x5d, 0xb5, 0xd6, 0x5d, 0x9f, 0x5d, 
+  0x85, 0xd8, 0x4d, 0xa4, 0xd7, 0xf5, 0xda, 0x5d, 
+  0x6e, 0x44, 0xdc, 0x4d, 0x64, 0xdb, 0x5d, 0x65, 
+  0xda, 0x4d, 0x8d, 0x2c, 0x4d, 0x8f, 0xd2, 0xb5, 
+  0xd8, 0xd2, 0xd0, 0x20, 0x01, 0x04, 
+
+ /* Char 72 is 35px wide @ 1768 */
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+  0x0c, 0xde, 0x20, 0x15, 0x01, 0x6e, 0x01, 0x04, 
+  0x01, 0x5e, 0x20, 0x15, 0x00, 0x10, 0x21, 
+
+ /* Char 73 is 14px wide @ 1783 */
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+  0x0c, 0xde, 0x20, 0x15, 0x00, 0x13, 0x61, 
+
+ /* Char 74 is 25px wide @ 1790 */
+ /*            **                                        */ 
+ /*            ****                                      */ 
+ /*           *****                                      */ 
+ /*           ****                                       */ 
+ /*           ****                                       */ 
+ /*          *****                                       */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          *****                                       */ 
+ /*           ****                                       */ 
+ /*           *****                                      */ 
+ /*            ******                                    */ 
+ /*            *******************************           */ 
+ /*             ******************************           */ 
+ /*               ****************************           */ 
+ /*                 **************************           */ 
+  0xb2, 0x02, 0x64, 0x02, 0x35, 0x02, 0x3f, 0x40, 
+  0x23, 0x50, 0x23, 0xe4, 0x40, 0x24, 0x50, 0x24, 
+  0x40, 0x24, 0x50, 0x24, 0x60, 0x22, 0x01, 0x3d, 
+  0x90, 0x12, 0xdb, 0xdf, 0xdd, 0xdd, 0x00, 0x10, 
+  0x21, 
+
+ /* Char 75 is 31px wide @ 1823 */
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                         ****                         */ 
+ /*                        *****                         */ 
+ /*                       *******                        */ 
+ /*                       ********                       */ 
+ /*                      **********                      */ 
+ /*                     *****  *****                     */ 
+ /*                    ******   *****                    */ 
+ /*                    *****     *****                   */ 
+ /*                   *****       *****                  */ 
+ /*                  *****         *****                 */ 
+ /*                 ******          *****                */ 
+ /*                ******            *****               */ 
+ /*               ******              *****              */ 
+ /*              ******                *****             */ 
+ /*             ******                  *****            */ 
+ /*           *******                    *****           */ 
+ /*          *******                      ****           */ 
+ /*          ******                        ***           */ 
+ /*          *****                          **           */ 
+ /*          ***                             *           */ 
+ /*          **                              *           */ 
+ /*          *                                           */ 
+  0x0c, 0xde, 0x20, 0x15, 0x01, 0x64, 0x02, 0x35, 
+  0x02, 0x27, 0x02, 0x18, 0x01, 0xfa, 0x01, 0xd5, 
+  0x25, 0x01, 0xb6, 0x35, 0x01, 0xa5, 0x55, 0x01, 
+  0x85, 0x75, 0x01, 0x65, 0x95, 0x01, 0x46, 0xa5, 
+  0x01, 0x26, 0xc5, 0xdf, 0x6d, 0x15, 0xdd, 0x6d, 
+  0x35, 0xdb, 0x6d, 0x55, 0xd8, 0x7d, 0x75, 0xd6, 
+  0x7d, 0x94, 0xd6, 0x6d, 0xb3, 0xd6, 0x5d, 0xd2, 
+  0xd6, 0x30, 0x11, 0x1d, 0x62, 0x01, 0x21, 0xd6, 
+  0x10, 0x52, 
+
+ /* Char 76 is 26px wide @ 1889 */
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+  0x0c, 0xde, 0x20, 0x15, 0xd6, 0xee, 0x40, 0x83, 
+
+
+ /* Char 77 is 43px wide @ 1897 */
+ /*          *************                               */ 
+ /*          ****************************                */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                    ***********************           */ 
+ /*                                  *********           */ 
+ /*                                 *********            */ 
+ /*                               *********              */ 
+ /*                             *********                */ 
+ /*                           *********                  */ 
+ /*                         *********                    */ 
+ /*                       *********                      */ 
+ /*                    **********                        */ 
+ /*                  *********                           */ 
+ /*                *********                             */ 
+ /*               ********                               */ 
+ /*               *****                                  */ 
+ /*               *****                                  */ 
+ /*               ********                               */ 
+ /*                *********                             */ 
+ /*                  *********                           */ 
+ /*                    **********                        */ 
+ /*                       *********                      */ 
+ /*                         *********                    */ 
+ /*                           *********                  */ 
+ /*                             *********                */ 
+ /*                               *********              */ 
+ /*                                 *********            */ 
+ /*                                  *********           */ 
+ /*                    ***********************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          ***************************                 */ 
+ /*          ***********                                 */ 
+  0x09, 0x9d, 0x00, 0x1b, 0xdf, 0xdb, 0xf0, 0x15, 
+  0x01, 0x1d, 0xa0, 0x1f, 0x90, 0x1e, 0x90, 0x1d, 
+  0x90, 0x1d, 0x90, 0x1d, 0x90, 0x1d, 0x90, 0x1d, 
+  0x90, 0x1c, 0xa0, 0x1c, 0x90, 0x1d, 0x90, 0x1e, 
+  0x80, 0x20, 0xf5, 0x02, 0x38, 0x02, 0x19, 0x02, 
+  0x19, 0x02, 0x1a, 0x02, 0x19, 0x02, 0x19, 0x02, 
+  0x19, 0x02, 0x19, 0x02, 0x19, 0x02, 0x19, 0x02, 
+  0x09, 0x01, 0x1d, 0xad, 0x6f, 0x01, 0x5d, 0x6d, 
+  0xed, 0xcb, 0x00, 0x14, 0xc1, 
+
+ /* Char 78 is 36px wide @ 1966 */
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                                   *******            */ 
+ /*                                  *******             */ 
+ /*                                 ******               */ 
+ /*                                ******                */ 
+ /*                               ******                 */ 
+ /*                              ******                  */ 
+ /*                             ******                   */ 
+ /*                           *******                    */ 
+ /*                          *******                     */ 
+ /*                         ******                       */ 
+ /*                        ******                        */ 
+ /*                       ******                         */ 
+ /*                     *******                          */ 
+ /*                    ******                            */ 
+ /*                   ******                             */ 
+ /*                 *******                              */ 
+ /*                ******                                */ 
+ /*               ******                                 */ 
+ /*             ******                                   */ 
+ /*            *******************************           */ 
+ /*           ********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+  0x0c, 0xde, 0x20, 0x15, 0x02, 0x07, 0x02, 0x07, 
+  0x02, 0x06, 0x02, 0x16, 0x02, 0x16, 0x02, 0x16, 
+  0x02, 0x16, 0x02, 0x07, 0x02, 0x07, 0x02, 0x06, 
+  0x02, 0x16, 0x02, 0x16, 0x02, 0x07, 0x02, 0x06, 
+  0x02, 0x16, 0x02, 0x07, 0x02, 0x06, 0x02, 0x16, 
+  0x02, 0x06, 0x02, 0x10, 0x13, 0xd7, 0x01, 0x4d, 
+  0x6f, 0x01, 0x50, 0x01, 0x02, 
+
+ /* Char 79 is 39px wide @ 2019 */
+ /*                      *********                       */ 
+ /*                   ***************                    */ 
+ /*                 *******************                  */ 
+ /*               ***********************                */ 
+ /*              **********     **********               */ 
+ /*             *******             *******              */ 
+ /*             ******               ******              */ 
+ /*            *****                   *****             */ 
+ /*            ****                     ****             */ 
+ /*           *****                     *****            */ 
+ /*           ****                       ****            */ 
+ /*          *****                       *****           */ 
+ /*          *****                       *****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          *****                       *****           */ 
+ /*          *****                       *****           */ 
+ /*           ****                       ****            */ 
+ /*           *****                     *****            */ 
+ /*           *****                     *****            */ 
+ /*            *****                   *****             */ 
+ /*             ******               ******              */ 
+ /*             *******             *******              */ 
+ /*              **********     **********               */ 
+ /*               ***********************                */ 
+ /*                 *******************                  */ 
+ /*                   ***************                    */ 
+ /*                      *********                       */ 
+  0x0a, 0x59, 0x01, 0xcd, 0x20, 0x17, 0xd6, 0x01, 
+  0x3d, 0xad, 0xfa, 0x5a, 0xdd, 0x7d, 0x07, 0xdc, 
+  0x6d, 0x26, 0xdb, 0x5d, 0x65, 0xda, 0x4d, 0x84, 
+  0xd9, 0x5d, 0x85, 0xd8, 0x4d, 0xa4, 0xd7, 0xf5, 
+  0xda, 0x5d, 0x6e, 0x34, 0xdc, 0x4d, 0x6f, 0x5d, 
+  0xa5, 0xd7, 0x4d, 0xa4, 0xd8, 0xf5, 0xd8, 0x5d, 
+  0x95, 0xd6, 0x5d, 0xb6, 0xd2, 0x6d, 0xc7, 0xd0, 
+  0x7d, 0xda, 0x5a, 0xdf, 0xda, 0x01, 0x3d, 0x60, 
+  0x17, 0xd2, 0x01, 0xc9, 0x00, 0x10, 0xe1, 
+
+ /* Char 80 is 30px wide @ 2090 */
+ /*          ********************************            */ 
+ /*          ********************************            */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                      ****             ****           */ 
+ /*                      ****             ****           */ 
+ /*                      ****             ****           */ 
+ /*                      ****             ****           */ 
+ /*                      ****             ****           */ 
+ /*                      ****             ****           */ 
+ /*                      ****             ****           */ 
+ /*                      ****             ****           */ 
+ /*                      ****             ****           */ 
+ /*                      *****           *****           */ 
+ /*                       ****           ****            */ 
+ /*                       ****           ****            */ 
+ /*                       *****         *****            */ 
+ /*                        *****       *****             */ 
+ /*                        *******   *******             */ 
+ /*                         ***************              */ 
+ /*                          *************               */ 
+ /*                           ***********                */ 
+ /*                             ******                   */ 
+  0x0c, 0xdf, 0x01, 0x4d, 0x7f, 0x01, 0x50, 0x13, 
+  0xe7, 0x4d, 0x04, 0x01, 0x35, 0xb5, 0x01, 0x4f, 
+  0x4b, 0x40, 0x15, 0x59, 0x50, 0x16, 0x57, 0x50, 
+  0x17, 0x73, 0x70, 0x18, 0xd2, 0x01, 0xad, 0x00, 
+  0x1c, 0xb0, 0x1f, 0x60, 0xa2, 
+
+ /* Char 81 is 39px wide @ 2127 */
+ /*                      *********                       */ 
+ /*                   ***************                    */ 
+ /*                 *******************                  */ 
+ /*               ***********************                */ 
+ /*              **********     **********               */ 
+ /*             *******             *******              */ 
+ /*             ******               ******              */ 
+ /*            *****                   *****             */ 
+ /*           *****                     ****             */ 
+ /*           *****                     *****            */ 
+ /*           ****                       ****            */ 
+ /*           ****                       *****           */ 
+ /*          *****                       *****           */ 
+ /*          ****                         ****           */ 
+ /*         *****                         ****           */ 
+ /*      ********                         ****           */ 
+ /*     *********                         ****           */ 
+ /*     *********                         ****           */ 
+ /*    ***** *****                       *****           */ 
+ /*   *****   ****                       *****           */ 
+ /*   ****    ****                       ****            */ 
+ /*   ****    *****                     *****            */ 
+ /*  *****     ****                     *****            */ 
+ /*  ****      *****                   *****             */ 
+ /*  ****       ******               ******              */ 
+ /* *****        ******             *******              */ 
+ /* ****          *********     **********               */ 
+ /* ****           **********************                */ 
+ /*   **            *******************                  */ 
+ /*                   ***************                    */ 
+ /*                       ********                       */ 
+  0x0a, 0x59, 0x01, 0xcd, 0x20, 0x17, 0xd6, 0x01, 
+  0x3d, 0xad, 0xfa, 0x5a, 0xdd, 0x7d, 0x07, 0xdc, 
+  0x6d, 0x26, 0xdb, 0x5d, 0x65, 0xd9, 0x5d, 0x84, 
+  0xd9, 0x5d, 0x85, 0xd8, 0x4d, 0xa4, 0xd8, 0x4d, 
+  0xa5, 0xd6, 0x5d, 0xa5, 0xd6, 0x4d, 0xc4, 0xd5, 
+  0x5d, 0xc4, 0xd2, 0x8d, 0xc4, 0xd1, 0xf9, 0xdc, 
+  0x4d, 0x05, 0x15, 0xda, 0x5c, 0x53, 0x4d, 0xa5, 
+  0xc4, 0x44, 0xda, 0x4d, 0x04, 0x45, 0xd8, 0x5c, 
+  0x55, 0x4d, 0x85, 0xc4, 0x65, 0xd6, 0x5d, 0x04, 
+  0x76, 0xd2, 0x6d, 0x05, 0x86, 0xd0, 0x7d, 0x04, 
+  0xa9, 0x5a, 0xd1, 0x4b, 0xd9, 0xd4, 0x2c, 0xd6, 
+  0x01, 0x7d, 0x20, 0x1d, 0x80, 0x01, 0x0e, 
+
+ /* Char 82 is 31px wide @ 2222 */
+ /*          ********************************            */ 
+ /*          ********************************            */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                       ****            ****           */ 
+ /*                       ****            ****           */ 
+ /*                       ****            ****           */ 
+ /*                       ****            ****           */ 
+ /*                       ****            ****           */ 
+ /*                       ****            ****           */ 
+ /*                       ****            ****           */ 
+ /*                       ****            ****           */ 
+ /*                      *****            ****           */ 
+ /*                     *******          *****           */ 
+ /*                    ********          ****            */ 
+ /*                  **********          ****            */ 
+ /*                ******* *****        *****            */ 
+ /*               *******   ****       *****             */ 
+ /*             ********    ******    ******             */ 
+ /*           ********       **************              */ 
+ /*          ********         ************               */ 
+ /*          ******            **********                */ 
+ /*          *****               ******                  */ 
+ /*          ***                                         */ 
+ /*          *                                           */ 
+  0x0c, 0xdf, 0x01, 0x4d, 0x7f, 0x01, 0x50, 0x14, 
+  0xe6, 0x4c, 0x40, 0x13, 0x5c, 0x40, 0x12, 0x7a, 
+  0x50, 0x11, 0x8a, 0x4d, 0xfa, 0xa4, 0xdd, 0x71, 
+  0x58, 0x5d, 0xc7, 0x34, 0x75, 0xdb, 0x84, 0x64, 
+  0x6d, 0x98, 0x7d, 0x1d, 0x98, 0x9c, 0xda, 0x6c, 
+  0xad, 0xb5, 0xd2, 0x6d, 0xd3, 0x02, 0x51, 0x08, 
+  0x61, 
+
+ /* Char 83 is 27px wide @ 2271 */
+ /*            **                                        */ 
+ /*            ****               ******                 */ 
+ /*           *****              *********               */ 
+ /*           ****              ***********              */ 
+ /*           ****             *************             */ 
+ /*          *****            ******   *****             */ 
+ /*          *****            ****      *****            */ 
+ /*          ****            *****       ****            */ 
+ /*          ****            ****        *****           */ 
+ /*          ****            ****         ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****           ****          ****           */ 
+ /*          ****          *****          ****           */ 
+ /*          ****          ****           ****           */ 
+ /*          *****        *****           ****           */ 
+ /*           ****        ****           *****           */ 
+ /*           *****      *****           ****            */ 
+ /*            *****   ******            ****            */ 
+ /*            **************            ****            */ 
+ /*             ************            *****            */ 
+ /*              **********                *             */ 
+ /*                ******                                */ 
+  0x06, 0x72, 0x02, 0x64, 0xd2, 0x6d, 0xd5, 0xd1, 
+  0x9d, 0xb4, 0xd1, 0xbd, 0xa4, 0xd0, 0xd0, 0xd8, 
+  0x5c, 0x63, 0x5d, 0x85, 0xc4, 0x65, 0xd7, 0x4c, 
+  0x57, 0x4d, 0x74, 0xc4, 0x85, 0xd6, 0x4c, 0x49, 
+  0x4d, 0x6e, 0x14, 0xb4, 0xa4, 0xd6, 0x4a, 0x5a, 
+  0x4d, 0x64, 0xa4, 0xb4, 0xd6, 0x58, 0x5b, 0x4d, 
+  0x74, 0x84, 0xb5, 0xd7, 0x56, 0x5b, 0x4d, 0x95, 
+  0x36, 0xc4, 0xd9, 0xd1, 0xc4, 0xda, 0xcc, 0x5d, 
+  0xba, 0xd3, 0x1d, 0xe6, 0x07, 0xb1, 
+
+ /* Char 84 is 28px wide @ 2341 */
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*          *********************************           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+ /*                                       ****           */ 
+  0x04, 0xee, 0x84, 0xd6, 0xe2, 0x01, 0x50, 0x24, 
+  0xe8, 0x40, 0x9a, 
+
+ /* Char 85 is 34px wide @ 2352 */
+ /*                   ************************           */ 
+ /*                ***************************           */ 
+ /*              *****************************           */ 
+ /*             ******************************           */ 
+ /*             *******                                  */ 
+ /*            ******                                    */ 
+ /*           *****                                      */ 
+ /*           *****                                      */ 
+ /*           ****                                       */ 
+ /*          *****                                       */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          *****                                       */ 
+ /*           ****                                       */ 
+ /*           *****                                      */ 
+ /*           *****                                      */ 
+ /*            ******                                    */ 
+ /*             *******                                  */ 
+ /*             ******************************           */ 
+ /*              *****************************           */ 
+ /*                ***************************           */ 
+ /*                   ************************           */ 
+  0x0d, 0x6d, 0xbd, 0xcd, 0xed, 0xa0, 0x11, 0xd9, 
+  0x01, 0x2d, 0x97, 0x02, 0x06, 0x02, 0x1f, 0x50, 
+  0x23, 0x40, 0x23, 0x50, 0x23, 0xe3, 0x40, 0x24, 
+  0x50, 0x24, 0x40, 0x24, 0xf5, 0x02, 0x46, 0x02, 
+  0x37, 0x02, 0x10, 0x12, 0xda, 0x01, 0x1d, 0xcd, 
+  0xed, 0xfd, 0xb0, 0x01, 0x02, 
+
+ /* Char 86 is 33px wide @ 2397 */
+ /*                                         **           */ 
+ /*                                       ****           */ 
+ /*                                    *******           */ 
+ /*                                 **********           */ 
+ /*                              ************            */ 
+ /*                            ************              */ 
+ /*                         ************                 */ 
+ /*                       ***********                    */ 
+ /*                    ************                      */ 
+ /*                  ***********                         */ 
+ /*                ***********                           */ 
+ /*             ***********                              */ 
+ /*           ***********                                */ 
+ /*          *********                                   */ 
+ /*          *******                                     */ 
+ /*          *******                                     */ 
+ /*          *********                                   */ 
+ /*           ***********                                */ 
+ /*             ***********                              */ 
+ /*                ***********                           */ 
+ /*                  ***********                         */ 
+ /*                    ************                      */ 
+ /*                       ***********                    */ 
+ /*                         ************                 */ 
+ /*                            ************              */ 
+ /*                              ************            */ 
+ /*                                 **********           */ 
+ /*                                    *******           */ 
+ /*                                       ****           */ 
+ /*                                         **           */ 
+  0x01, 0xc2, 0x02, 0x44, 0x02, 0x17, 0x01, 0xea, 
+  0x01, 0xbc, 0x01, 0xac, 0x01, 0x9c, 0x01, 0xab, 
+  0x01, 0xac, 0x01, 0xab, 0x01, 0xbb, 0x01, 0xab, 
+  0x01, 0xbb, 0x01, 0xc9, 0x01, 0xff, 0x70, 0x21, 
+  0x90, 0x20, 0xb0, 0x1f, 0xb0, 0x20, 0xb0, 0x1f, 
+  0xb0, 0x1f, 0xc0, 0x1f, 0xb0, 0x1f, 0xc0, 0x1f, 
+  0xc0, 0x1e, 0xc0, 0x1f, 0xa0, 0x21, 0x70, 0x24, 
+  0x40, 0x26, 0x20, 0x9a, 
+
+ /* Char 87 is 46px wide @ 2457 */
+ /*                                        ***           */ 
+ /*                                  *********           */ 
+ /*                              *************           */ 
+ /*                         ******************           */ 
+ /*                     ********************             */ 
+ /*                  ******************                  */ 
+ /*              ******************                      */ 
+ /*           ****************                           */ 
+ /*          *************                               */ 
+ /*          *********                                   */ 
+ /*          *******                                     */ 
+ /*          *********                                   */ 
+ /*          ***********                                 */ 
+ /*            ************                              */ 
+ /*               ************                           */ 
+ /*                 *************                        */ 
+ /*                    *************                     */ 
+ /*                       *************                  */ 
+ /*                          *************               */ 
+ /*                             **********               */ 
+ /*                               ********               */ 
+ /*                             **********               */ 
+ /*                          ************                */ 
+ /*                       ************                   */ 
+ /*                    ************                      */ 
+ /*                  ***********                         */ 
+ /*               ***********                            */ 
+ /*             ***********                              */ 
+ /*          ***********                                 */ 
+ /*          ********                                    */ 
+ /*          *******                                     */ 
+ /*          *********                                   */ 
+ /*          *************                               */ 
+ /*           ****************                           */ 
+ /*              ******************                      */ 
+ /*                  ******************                  */ 
+ /*                      *******************             */ 
+ /*                         ******************           */ 
+ /*                              *************           */ 
+ /*                                   ********           */ 
+ /*                                        ***           */ 
+  0x04, 0xf3, 0x01, 0xf9, 0x01, 0xbd, 0x00, 0x16, 
+  0xd5, 0x01, 0x2d, 0x70, 0x11, 0xd5, 0x01, 0x2d, 
+  0x50, 0x13, 0xd3, 0x01, 0x7d, 0x00, 0x1b, 0x90, 
+  0x1f, 0x70, 0x21, 0x90, 0x1f, 0xb0, 0x1f, 0xc0, 
+  0x1f, 0xc0, 0x1e, 0xd0, 0x01, 0xed, 0x00, 0x1e, 
+  0xd0, 0x01, 0xed, 0x00, 0x1e, 0xa0, 0x20, 0x80, 
+  0x1e, 0xa0, 0x1b, 0xc0, 0x19, 0xc0, 0x19, 0xc0, 
+  0x1a, 0xb0, 0x1a, 0xb0, 0x1b, 0xb0, 0x1a, 0xb0, 
+  0x1d, 0x80, 0x20, 0x70, 0x21, 0x90, 0x1f, 0xd0, 
+  0x01, 0xcd, 0x30, 0x1b, 0xd5, 0x01, 0xad, 0x50, 
+  0x1a, 0xd6, 0x01, 0x8d, 0x50, 0x1b, 0xd0, 0x02, 
+  0x08, 0x02, 0x53, 0x0c, 0xe1, 
+
+ /* Char 88 is 32px wide @ 2550 */
+ /*          *                               *           */ 
+ /*          **                             **           */ 
+ /*          ****                         ****           */ 
+ /*          ******                      *****           */ 
+ /*          *******                    ******           */ 
+ /*           ********                *******            */ 
+ /*             *******              ******              */ 
+ /*              ********          *******               */ 
+ /*                *******        *******                */ 
+ /*                 *******     *******                  */ 
+ /*                   *******  *******                   */ 
+ /*                    *************                     */ 
+ /*                      **********                      */ 
+ /*                       ********                       */ 
+ /*                       ********                       */ 
+ /*                     ************                     */ 
+ /*                    ****** *******                    */ 
+ /*                   ******    *******                  */ 
+ /*                 *******      *******                 */ 
+ /*                ******          *******               */ 
+ /*              *******            *******              */ 
+ /*             *******               *******            */ 
+ /*           *******                  *******           */ 
+ /*          *******                     *****           */ 
+ /*          *****                        ****           */ 
+ /*          ****                           **           */ 
+ /*          **                              *           */ 
+ /*          *                                           */ 
+  0x03, 0x11, 0x01, 0x31, 0xd6, 0x20, 0x11, 0x2d, 
+  0x64, 0xdc, 0x4d, 0x66, 0xd9, 0x5d, 0x67, 0xd7, 
+  0x6d, 0x78, 0xd3, 0x7d, 0xa7, 0xd1, 0x6d, 0xd8, 
+  0xa7, 0x01, 0x17, 0x87, 0x01, 0x37, 0x57, 0x01, 
+  0x77, 0x27, 0x01, 0x9d, 0x00, 0x1d, 0xa0, 0x1f, 
+  0xf8, 0x01, 0xec, 0x01, 0xb6, 0x17, 0x01, 0x96, 
+  0x47, 0x01, 0x57, 0x67, 0x01, 0x36, 0xa7, 0xde, 
+  0x7c, 0x7d, 0xc7, 0xd2, 0x7d, 0x87, 0xd5, 0x7d, 
+  0x67, 0xd8, 0x5d, 0x65, 0xdb, 0x4d, 0x64, 0xde, 
+  0x2d, 0x62, 0x01, 0x21, 0xd6, 0x10, 0xba, 
+
+ /* Char 89 is 30px wide @ 2629 */
+ /*                                          *           */ 
+ /*                                        ***           */ 
+ /*                                       ****           */ 
+ /*                                     ******           */ 
+ /*                                   ********           */ 
+ /*                                 ********             */ 
+ /*                                *******               */ 
+ /*                              ********                */ 
+ /*                            ********                  */ 
+ /*                           *******                    */ 
+ /*                         ********                     */ 
+ /*                        *******                       */ 
+ /*          ********************                        */ 
+ /*          ******************                          */ 
+ /*          ******************                          */ 
+ /*          ********************                        */ 
+ /*                        *******                       */ 
+ /*                         ********                     */ 
+ /*                           *******                    */ 
+ /*                            ********                  */ 
+ /*                              ********                */ 
+ /*                                ********              */ 
+ /*                                 ********             */ 
+ /*                                   ********           */ 
+ /*                                     ******           */ 
+ /*                                       ****           */ 
+ /*                                        ***           */ 
+ /*                                          *           */ 
+  0x01, 0xd1, 0x02, 0x53, 0x02, 0x44, 0x02, 0x26, 
+  0x02, 0x08, 0x01, 0xe8, 0x01, 0xf7, 0x01, 0xf8, 
+  0x01, 0xe8, 0x01, 0xf7, 0x01, 0xf8, 0x01, 0xf7, 
+  0x01, 0x3d, 0x70, 0x14, 0xfd, 0x50, 0x16, 0xd7, 
+  0x02, 0x27, 0x02, 0x28, 0x02, 0x27, 0x02, 0x28, 
+  0x02, 0x28, 0x02, 0x28, 0x02, 0x18, 0x02, 0x28, 
+  0x02, 0x26, 0x02, 0x44, 0x02, 0x53, 0x02, 0x71, 
+  0x06, 0x61, 
+
+ /* Char 90 is 29px wide @ 2687 */
+ /*          ****                                        */ 
+ /*          *****                        ****           */ 
+ /*          *******                      ****           */ 
+ /*          ********                     ****           */ 
+ /*          **********                   ****           */ 
+ /*          ***********                  ****           */ 
+ /*          ****  *******                ****           */ 
+ /*          ****   *******               ****           */ 
+ /*          ****     ******              ****           */ 
+ /*          ****      *******            ****           */ 
+ /*          ****        ******           ****           */ 
+ /*          ****         ******          ****           */ 
+ /*          ****          *******        ****           */ 
+ /*          ****            ******       ****           */ 
+ /*          ****             ******      ****           */ 
+ /*          ****              ******     ****           */ 
+ /*          ****                ******   ****           */ 
+ /*          ****                 ******  ****           */ 
+ /*          ****                  ****** ****           */ 
+ /*          ****                    *********           */ 
+ /*          ****                     ********           */ 
+ /*          ****                      *******           */ 
+ /*          ****                       ******           */ 
+ /*          ****                        *****           */ 
+  0x06, 0x54, 0x02, 0x45, 0xdb, 0x4d, 0x67, 0xd9, 
+  0x4d, 0x68, 0xd8, 0x4d, 0x6a, 0xd6, 0x4d, 0x6b, 
+  0xd5, 0x4d, 0x64, 0x27, 0xd3, 0x4d, 0x64, 0x37, 
+  0xd2, 0x4d, 0x64, 0x56, 0xd1, 0x4d, 0x64, 0x67, 
+  0xc4, 0xd6, 0x48, 0x6b, 0x4d, 0x64, 0x96, 0xa4, 
+  0xd6, 0x4a, 0x78, 0x4d, 0x64, 0xc6, 0x74, 0xd6, 
+  0x4d, 0x06, 0x64, 0xd6, 0x4d, 0x16, 0x54, 0xd6, 
+  0x4d, 0x36, 0x34, 0xd6, 0x4d, 0x46, 0x24, 0xd6, 
+  0x4d, 0x56, 0x14, 0xd6, 0x4d, 0x79, 0xd6, 0x4d, 
+  0x88, 0xd6, 0x4d, 0x97, 0xd6, 0x4d, 0xa6, 0xd6, 
+  0x4d, 0xb5, 0x09, 0xa1, 
+
+ /* Char 91 is 17px wide @ 2771 */
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+  0x0f, 0x80, 0x23, 0xe2, 0x54, 0x01, 0xbe, 0x54, 
+  0x02, 0xd1, 
+
+ /* Char 92 is 20px wide @ 2781 */
+ /*                                            ****      */ 
+ /*                                         *******      */ 
+ /*                                      **********      */ 
+ /*                                   ************       */ 
+ /*                                ************          */ 
+ /*                              ************            */ 
+ /*                           ************               */ 
+ /*                        ************                  */ 
+ /*                     ************                     */ 
+ /*                  ************                        */ 
+ /*                ************                          */ 
+ /*             ************                             */ 
+ /*          ************                                */ 
+ /*       ************                                   */ 
+ /*     ************                                     */ 
+ /*  ************                                        */ 
+ /* **********                                           */ 
+ /* *******                                              */ 
+ /* ****                                                 */ 
+ /* **                                                   */ 
+  0x01, 0xf4, 0x02, 0x17, 0x01, 0xea, 0x01, 0xbc, 
+  0x01, 0x9c, 0x01, 0xac, 0x01, 0x9c, 0x01, 0x9c, 
+  0x01, 0x9c, 0x01, 0x9c, 0x01, 0xac, 0x01, 0x9c, 
+  0x01, 0x9c, 0x01, 0x9c, 0x01, 0xac, 0x01, 0x9c, 
+  0x01, 0xba, 0x01, 0xe7, 0x02, 0x14, 0x02, 0x42, 
+  0x02, 0x61, 
+
+ /* Char 93 is 17px wide @ 2823 */
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+  0xe4, 0x01, 0xbe, 0x54, 0x50, 0x23, 0xe2, 0x00, 
+  0x13, 0x11, 
+
+ /* Char 94 is 28px wide @ 2833 */
+ /*                           *                          */ 
+ /*                          ***                         */ 
+ /*                          *****                       */ 
+ /*                         ********                     */ 
+ /*                          ********                    */ 
+ /*                           *********                  */ 
+ /*                             ********                 */ 
+ /*                               ********               */ 
+ /*                                 ********             */ 
+ /*                                  ********            */ 
+ /*                                    *******           */ 
+ /*                                      *****           */ 
+ /*                                    *******           */ 
+ /*                                  ********            */ 
+ /*                                 ********             */ 
+ /*                               ********               */ 
+ /*                             ********                 */ 
+ /*                           *********                  */ 
+ /*                          ********                    */ 
+ /*                         ********                     */ 
+ /*                          *****                       */ 
+ /*                          ***                         */ 
+ /*                           *                          */ 
+  0x07, 0x61, 0x02, 0x63, 0x02, 0x55, 0x02, 0x28, 
+  0x02, 0x18, 0x02, 0x19, 0x02, 0x18, 0x02, 0x28, 
+  0x02, 0x28, 0x02, 0x18, 0x02, 0x27, 0x02, 0x35, 
+  0x02, 0x17, 0x01, 0xf8, 0x01, 0xf8, 0x01, 0xe8, 
+  0x01, 0xe8, 0x01, 0xe9, 0x01, 0xe8, 0x01, 0xf8, 
+  0x02, 0x15, 0x02, 0x33, 0x02, 0x61, 0x0a, 0x91, 
+
+
+ /* Char 95 is 25px wide @ 2881 */
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+  0xe4, 0xe0, 0x16, 0x05, 0x81, 
+
+ /* Char 96 is 19px wide @ 2886 */
+ /*                                           **         */ 
+ /*                                           ***        */ 
+ /*                                          *****       */ 
+ /*                                         *****        */ 
+ /*                                        *****         */ 
+ /*                                       *****          */ 
+ /*                                      *****           */ 
+ /*                                       ***            */ 
+ /*                                        *             */ 
+  0x0b, 0xa2, 0x02, 0x63, 0x02, 0x45, 0x02, 0x25, 
+  0x02, 0x25, 0x02, 0x25, 0x02, 0x25, 0x02, 0x43, 
+  0x02, 0x61, 0x00, 0x16, 0xc1, 
+
+ /* Char 97 is 26px wide @ 2907 */
+ /*               ******                                 */ 
+ /*             **********                               */ 
+ /*            ************                              */ 
+ /*           *************      ****                    */ 
+ /*           *****   ******     ****                    */ 
+ /*          *****      ****      ****                   */ 
+ /*          *****      *****     ****                   */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****    *****                   */ 
+ /*          ****        ****    ****                    */ 
+ /*          ****       *****  ******                    */ 
+ /*          ************************                    */ 
+ /*           **********************                     */ 
+ /*           *********************                      */ 
+ /*           *******************                        */ 
+  0x06, 0xa6, 0x02, 0x0a, 0x01, 0xdc, 0x01, 0xbd, 
+  0x06, 0x40, 0x11, 0x53, 0x65, 0x4d, 0xf5, 0x64, 
+  0x64, 0xde, 0x56, 0x55, 0x4d, 0xee, 0x34, 0x84, 
+  0x54, 0xde, 0x48, 0x44, 0x5d, 0xe4, 0x84, 0x44, 
+  0xdf, 0x47, 0x52, 0x6d, 0xfd, 0xb0, 0x11, 0xd9, 
+  0x01, 0x2d, 0x80, 0x13, 0xd6, 0x00, 0x10, 0xf1, 
+
+
+ /* Char 98 is 29px wide @ 2955 */
+ /*           ***********************************        */ 
+ /*           ************************************       */ 
+ /*           ************************************       */ 
+ /*          *************************************       */ 
+ /*          ****               *****                    */ 
+ /*          ****                ****                    */ 
+ /*          ****                ****                    */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*           ****               *****                   */ 
+ /*           ****               ****                    */ 
+ /*           *****             *****                    */ 
+ /*            *****           ******                    */ 
+ /*            ********      *******                     */ 
+ /*             *******************                      */ 
+ /*               ****************                       */ 
+ /*                *************                         */ 
+ /*                   *******                            */ 
+  0x0c, 0xe0, 0x17, 0xd4, 0xf0, 0x18, 0xd2, 0x01, 
+  0x9d, 0x24, 0xd2, 0x5d, 0xff, 0x4d, 0x34, 0xdf, 
+  0xe3, 0x4d, 0x44, 0xdf, 0x4d, 0x25, 0xdf, 0x4d, 
+  0x24, 0x01, 0x15, 0xd0, 0x50, 0x12, 0x5b, 0x60, 
+  0x12, 0x86, 0x70, 0x14, 0xd6, 0x01, 0x7d, 0x30, 
+  0x19, 0xd0, 0x01, 0xe7, 0x0d, 0xf1, 
+
+ /* Char 99 is 24px wide @ 3001 */
+ /*                   *******                            */ 
+ /*                *************                         */ 
+ /*              ****************                        */ 
+ /*             *******************                      */ 
+ /*            *******       ******                      */ 
+ /*            *****           *****                     */ 
+ /*           *****             *****                    */ 
+ /*           ****               ****                    */ 
+ /*          *****               ****                    */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          *****               *****                   */ 
+ /*           ****               ****                    */ 
+ /*           ****                 **                    */ 
+  0x0a, 0x27, 0x01, 0xed, 0x00, 0x19, 0xd3, 0x01, 
+  0x7d, 0x60, 0x14, 0x77, 0x60, 0x14, 0x5b, 0x50, 
+  0x12, 0x5d, 0x05, 0x01, 0x14, 0xd2, 0x4d, 0xf5, 
+  0xd2, 0x4d, 0xfe, 0x44, 0xd4, 0x4d, 0xe5, 0xd2, 
+  0x5d, 0xf4, 0xd2, 0x40, 0x11, 0x4d, 0x42, 0x0a, 
+  0x31, 
+
+ /* Char 100 is 29px wide @ 3042 */
+ /*                   *******                            */ 
+ /*                *************                         */ 
+ /*              *****************                       */ 
+ /*             *******************                      */ 
+ /*            ********      *******                     */ 
+ /*            *****           ******                    */ 
+ /*           *****             *****                    */ 
+ /*           ****               ****                    */ 
+ /*           ****               *****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                ****                    */ 
+ /*          ****                ****                    */ 
+ /*          *****              *****                    */ 
+ /*          ************************************        */ 
+ /*           ************************************       */ 
+ /*           ************************************       */ 
+ /*           ************************************       */ 
+  0x0a, 0x27, 0x01, 0xed, 0x00, 0x19, 0xd4, 0x01, 
+  0x6d, 0x60, 0x14, 0x86, 0x70, 0x13, 0x5b, 0x60, 
+  0x11, 0x5d, 0x05, 0x01, 0x14, 0xd2, 0x40, 0x11, 
+  0x4d, 0x25, 0xde, 0xe3, 0x4d, 0x44, 0xde, 0xf4, 
+  0xd3, 0x4d, 0xf5, 0xd1, 0x5d, 0xf0, 0x18, 0xd4, 
+  0xe1, 0x01, 0x80, 0xfe, 
+
+ /* Char 101 is 28px wide @ 3086 */
+ /*                  ********                            */ 
+ /*                *************                         */ 
+ /*              *****************                       */ 
+ /*             *******************                      */ 
+ /*            *******  ****  ******                     */ 
+ /*            *****    ****   *****                     */ 
+ /*           *****     ****    *****                    */ 
+ /*           ****      ****     ****                    */ 
+ /*           ****      ****     *****                   */ 
+ /*          ****       ****      ****                   */ 
+ /*          ****       ****      ****                   */ 
+ /*          ****       ****      ****                   */ 
+ /*          ****       ****      ****                   */ 
+ /*          ****       ****     *****                   */ 
+ /*          ****       ****     ****                    */ 
+ /*          ****       ****    *****                    */ 
+ /*          *****      ****  ******                     */ 
+ /*           ****      ************                     */ 
+ /*           ****      ***********                      */ 
+ /*                     *********                        */ 
+ /*                     ******                           */ 
+  0x0a, 0x18, 0x01, 0xed, 0x00, 0x19, 0xd4, 0x01, 
+  0x6d, 0x60, 0x14, 0x72, 0x42, 0x60, 0x13, 0x54, 
+  0x43, 0x50, 0x12, 0x55, 0x44, 0x50, 0x11, 0x46, 
+  0x45, 0x40, 0x11, 0x46, 0x45, 0x5d, 0xee, 0x24, 
+  0x74, 0x64, 0xde, 0x47, 0x45, 0x5d, 0xe4, 0x74, 
+  0x54, 0xdf, 0x47, 0x44, 0x5d, 0xf5, 0x64, 0x26, 
+  0x01, 0x24, 0x6c, 0x01, 0x24, 0x6b, 0x01, 0xd9, 
+  0x01, 0xf6, 0x0d, 0xe1, 
+
+ /* Char 102 is 20px wide @ 3146 */
+ /*          *******************************             */ 
+ /*          *********************************           */ 
+ /*          ***********************************         */ 
+ /*          ***********************************         */ 
+ /*                               ****     ******        */ 
+ /*                               ****      *****        */ 
+ /*                               ****       *****       */ 
+ /*                               ****        ****       */ 
+ /*                               ****        ****       */ 
+ /*                               ****        ****       */ 
+ /*                               ****        ****       */ 
+ /*                               ****        ****       */ 
+ /*                               ****        ****       */ 
+ /*                               ****       *****       */ 
+ /*                                            **        */ 
+  0x0c, 0xd0, 0x13, 0xd8, 0x01, 0x5d, 0x6f, 0x01, 
+  0x70, 0x1a, 0x45, 0x60, 0x19, 0x46, 0x50, 0x19, 
+  0x47, 0x50, 0x18, 0xe4, 0x48, 0x40, 0x18, 0x47, 
+  0x50, 0x25, 0x20, 0x2f, 
+
+ /* Char 103 is 29px wide @ 3174 */
+ /*                   *******                            */ 
+ /*  ***           *************                         */ 
+ /*  ****         ****************                       */ 
+ /*  ****        ******************                      */ 
+ /* *****       *******      *******                     */ 
+ /* ****       ******          *****                     */ 
+ /* ****       *****            *****                    */ 
+ /* ****       ****              ****                    */ 
+ /* ****      *****              ****                    */ 
+ /* ****      ****                ****                   */ 
+ /* ****      ****                ****                   */ 
+ /* ****      ****                ****                   */ 
+ /* ****      ****                ****                   */ 
+ /* *****     ****                ****                   */ 
+ /*  ****     *****               ****                   */ 
+ /*  *****     ****               ****                   */ 
+ /*   ******   *****              ****                   */ 
+ /*   ********************************                   */ 
+ /*    ******************************                    */ 
+ /*      ****************************                    */ 
+ /*        **************************                    */ 
+  0x0a, 0x27, 0xdf, 0x3b, 0xd0, 0xdc, 0x49, 0xd3, 
+  0xda, 0x48, 0xd5, 0xd8, 0x57, 0x76, 0x7d, 0x74, 
+  0x76, 0xa5, 0xd7, 0x47, 0x5c, 0x5d, 0x64, 0x74, 
+  0xd1, 0x4d, 0x64, 0x65, 0xd1, 0x4d, 0x64, 0x6e, 
+  0x24, 0xd3, 0x4d, 0x55, 0x54, 0xd3, 0x4d, 0x64, 
+  0x55, 0xd2, 0x4d, 0x65, 0x54, 0xd2, 0x4d, 0x76, 
+  0x35, 0xd1, 0x4d, 0x70, 0x14, 0xd8, 0x01, 0x2d, 
+  0xbd, 0xfd, 0xdd, 0xd0, 0x01, 0x0b, 
+
+ /* Char 104 is 29px wide @ 3236 */
+ /*          ************************************        */ 
+ /*          *************************************       */ 
+ /*          *************************************       */ 
+ /*          *************************************       */ 
+ /*                              ****                    */ 
+ /*                               ***                    */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                              ****                    */ 
+ /*                             *****                    */ 
+ /*                           *******                    */ 
+ /*          ***********************                     */ 
+ /*          **********************                      */ 
+ /*          *********************                       */ 
+ /*          ******************                          */ 
+  0x0c, 0xd0, 0x18, 0xd3, 0xe1, 0x01, 0x90, 0x17, 
+  0x40, 0x25, 0x30, 0x25, 0xe4, 0x40, 0x23, 0x40, 
+  0x23, 0x50, 0x21, 0x7d, 0xfd, 0xa0, 0x11, 0xd9, 
+  0x01, 0x2d, 0x80, 0x13, 0xd5, 0x00, 0x14, 0x51, 
+
+
+ /* Char 105 is 13px wide @ 3268 */
+ /*                                          *           */ 
+ /*          *************************     *****         */ 
+ /*          *************************     *****         */ 
+ /*          *************************     *****         */ 
+ /*          *************************      ***          */ 
+ /*                                          *           */ 
+  0x0b, 0x91, 0xd6, 0xe1, 0xdc, 0x55, 0xd4, 0xdc, 
+  0x63, 0x02, 0x61, 0x0c, 0xe1, 
+
+ /* Char 106 is 13px wide @ 3281 */
+ /* ****                                                 */ 
+ /* ****                                                 */ 
+ /* *****                                                */ 
+ /*  ******                                  *           */ 
+ /*  *********************************     *****         */ 
+ /*   ********************************     *****         */ 
+ /*    *******************************     *****         */ 
+ /*      *****************************      ***          */ 
+ /*                                          *           */ 
+  0xe4, 0xf0, 0x24, 0x50, 0x24, 0x60, 0x16, 0x1b, 
+  0x01, 0x55, 0x5a, 0x01, 0x45, 0x5b, 0x01, 0x35, 
+  0x5d, 0x00, 0x11, 0x63, 0x02, 0x61, 0x0c, 0xe1, 
+
+
+ /* Char 107 is 26px wide @ 3305 */
+ /*          ************************************        */ 
+ /*          *************************************       */ 
+ /*          *************************************       */ 
+ /*          *************************************       */ 
+ /*                      ****                            */ 
+ /*                     ******                           */ 
+ /*                    *******                           */ 
+ /*                   *********                          */ 
+ /*                  ***********                         */ 
+ /*                 ******  ******                       */ 
+ /*                ******    ******                      */ 
+ /*              *******      ******                     */ 
+ /*             *******        ******                    */ 
+ /*            *******          ******                   */ 
+ /*          ********            *****                   */ 
+ /*          *******              ****                   */ 
+ /*          *****                 ***                   */ 
+ /*          ****                   **                   */ 
+ /*          ***                     *                   */ 
+ /*          *                                           */ 
+  0x0c, 0xd0, 0x18, 0xd3, 0xe1, 0x01, 0x9d, 0xe4, 
+  0x02, 0x36, 0x02, 0x17, 0x02, 0x09, 0x01, 0xeb, 
+  0x01, 0xc6, 0x26, 0x01, 0x96, 0x46, 0x01, 0x67, 
+  0x66, 0x01, 0x47, 0x86, 0x01, 0x27, 0xa6, 0xde, 
+  0x8c, 0x5d, 0xe7, 0xd1, 0x4d, 0xe5, 0xd4, 0x3d, 
+  0xe4, 0xd6, 0x2d, 0xe3, 0xd8, 0x1d, 0xe1, 0x08, 
+  0x61, 
+
+ /* Char 108 is 15px wide @ 3354 */
+ /*              ********************************        */ 
+ /*            ***********************************       */ 
+ /*           ************************************       */ 
+ /*           ************************************       */ 
+ /*          ******                                      */ 
+ /*          *****                                       */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+  0x0d, 0x10, 0x14, 0xd5, 0x01, 0x7d, 0x3f, 0x01, 
+  0x8d, 0x26, 0x02, 0x25, 0x02, 0x3f, 0x40, 0xb7, 
+
+
+ /* Char 109 is 42px wide @ 3370 */
+ /*          ************************                    */ 
+ /*          ************************                    */ 
+ /*          ************************                    */ 
+ /*          *************************                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                              *****                   */ 
+ /*                             *****                    */ 
+ /*                           *******                    */ 
+ /*          ***********************                     */ 
+ /*          ***********************                     */ 
+ /*          ***********************                     */ 
+ /*          ****************** *****                    */ 
+ /*                              ****                    */ 
+ /*                              ****                    */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                              *****                   */ 
+ /*                             *****                    */ 
+ /*                           *******                    */ 
+ /*          ***********************                     */ 
+ /*          ***********************                     */ 
+ /*          *********************                       */ 
+ /*          *******************                         */ 
+  0x0c, 0xde, 0x1d, 0xbd, 0xfd, 0xc0, 0x24, 0xe6, 
+  0x40, 0x23, 0x50, 0x22, 0x50, 0x21, 0x7d, 0xfe, 
+  0x1d, 0xa0, 0x11, 0xd5, 0x15, 0x02, 0x4f, 0x40, 
+  0x25, 0xe4, 0x40, 0x23, 0x50, 0x22, 0x50, 0x21, 
+  0x7d, 0xff, 0xda, 0x01, 0x1d, 0x80, 0x13, 0xd6, 
+  0x0d, 0xc1, 
+
+ /* Char 110 is 29px wide @ 3412 */
+ /*          ************************                    */ 
+ /*          ************************                    */ 
+ /*          ************************                    */ 
+ /*          *************************                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                              *****                   */ 
+ /*                              ****                    */ 
+ /*                             *****                    */ 
+ /*                           *******                    */ 
+ /*          ***********************                     */ 
+ /*          **********************                      */ 
+ /*          *********************                       */ 
+ /*          ******************                          */ 
+  0x0c, 0xde, 0x1d, 0xbd, 0xfd, 0xc0, 0x24, 0xe6, 
+  0x40, 0x23, 0x50, 0x23, 0x40, 0x23, 0x50, 0x21, 
+  0x7d, 0xfd, 0xa0, 0x11, 0xd9, 0x01, 0x2d, 0x80, 
+  0x13, 0xd5, 0x00, 0x11, 0x11, 
+
+ /* Char 111 is 30px wide @ 3441 */
+ /*                   *******                            */ 
+ /*                *************                         */ 
+ /*              *****************                       */ 
+ /*             *******************                      */ 
+ /*            *******       *******                     */ 
+ /*            *****           *****                     */ 
+ /*           *****             *****                    */ 
+ /*           ****               ****                    */ 
+ /*          *****               *****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          *****               *****                   */ 
+ /*           ****               ****                    */ 
+ /*           *****             *****                    */ 
+ /*            *****           *****                     */ 
+ /*            *******       *******                     */ 
+ /*             *******************                      */ 
+ /*              *****************                       */ 
+ /*                *************                         */ 
+ /*                   *******                            */ 
+  0x0a, 0x27, 0x01, 0xed, 0x00, 0x19, 0xd4, 0x01, 
+  0x6d, 0x60, 0x14, 0x77, 0x70, 0x13, 0x5b, 0x50, 
+  0x12, 0x5d, 0x05, 0x01, 0x14, 0xd2, 0x4d, 0xf5, 
+  0xd2, 0x5d, 0xee, 0x24, 0xd4, 0x4d, 0xe5, 0xd2, 
+  0x5d, 0xf4, 0xd2, 0x40, 0x11, 0x5d, 0x05, 0x01, 
+  0x25, 0xb5, 0x01, 0x37, 0x77, 0x01, 0x4d, 0x60, 
+  0x16, 0xd4, 0x01, 0x9d, 0x00, 0x1e, 0x70, 0x01, 
+  0x13, 
+
+ /* Char 112 is 29px wide @ 3498 */
+ /* *********************************                    */ 
+ /* *********************************                    */ 
+ /* *********************************                    */ 
+ /* **********************************                   */ 
+ /*           *****               ****                   */ 
+ /*           ****                ****                   */ 
+ /*           ****                ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          *****               ****                    */ 
+ /*           ****               ****                    */ 
+ /*           *****             *****                    */ 
+ /*           ******           *****                     */ 
+ /*            *******      ********                     */ 
+ /*             *******************                      */ 
+ /*              ****************                        */ 
+ /*                *************                         */ 
+ /*                   *******                            */ 
+  0x0c, 0x40, 0x15, 0xe1, 0xd6, 0x01, 0x6d, 0xf5, 
+  0xd2, 0x4d, 0xff, 0x4d, 0x34, 0xde, 0xe3, 0x4d, 
+  0x44, 0xde, 0x5d, 0x24, 0x01, 0x14, 0xd2, 0x40, 
+  0x11, 0x5d, 0x05, 0x01, 0x16, 0xb5, 0x01, 0x37, 
+  0x68, 0x01, 0x4d, 0x60, 0x16, 0xd3, 0x01, 0xad, 
+  0x00, 0x1e, 0x70, 0xdf, 
+
+ /* Char 113 is 29px wide @ 3542 */
+ /*                   *******                            */ 
+ /*                *************                         */ 
+ /*              *****************                       */ 
+ /*             *******************                      */ 
+ /*            *******      ********                     */ 
+ /*           ******           *****                     */ 
+ /*           *****             *****                    */ 
+ /*           ****               ****                    */ 
+ /*          *****               ****                    */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*           ****                ****                   */ 
+ /*           ****                ****                   */ 
+ /*           *****               ****                   */ 
+ /* **********************************                   */ 
+ /* *********************************                    */ 
+ /* *********************************                    */ 
+ /* *********************************                    */ 
+  0x0a, 0x27, 0x01, 0xed, 0x00, 0x19, 0xd4, 0x01, 
+  0x6d, 0x60, 0x14, 0x76, 0x80, 0x12, 0x6b, 0x50, 
+  0x12, 0x5d, 0x05, 0x01, 0x14, 0xd2, 0x4d, 0xf5, 
+  0xd2, 0x4d, 0xfe, 0x34, 0xd4, 0x4d, 0xff, 0x4d, 
+  0x34, 0xdf, 0x5d, 0x24, 0xd5, 0x01, 0x6d, 0x50, 
+  0x15, 0xe1, 0x00, 0x10, 0xb1, 
+
+ /* Char 114 is 20px wide @ 3587 */
+ /*          ************************                    */ 
+ /*          ************************                    */ 
+ /*          ************************                    */ 
+ /*          ************************                    */ 
+ /*                              *****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                               ****                   */ 
+ /*                              *****                   */ 
+ /*                               ***                    */ 
+  0x0c, 0xde, 0x2d, 0xb0, 0x24, 0x50, 0x24, 0xe6, 
+  0x40, 0x23, 0x50, 0x24, 0x30, 0x3b, 
+
+ /* Char 115 is 23px wide @ 3601 */
+ /*           ***           ******                       */ 
+ /*           ****         ********                      */ 
+ /*          *****        **********                     */ 
+ /*          *****       ************                    */ 
+ /*          ****        *****  *****                    */ 
+ /*          ****       *****    *****                   */ 
+ /*          ****       ****      ****                   */ 
+ /*          ****       ****      ****                   */ 
+ /*          ****      *****      ****                   */ 
+ /*          ****      ****       ****                   */ 
+ /*          *****    *****       ****                   */ 
+ /*           ****   *****        ****                   */ 
+ /*           ************       *****                   */ 
+ /*            **********        ****                    */ 
+ /*             ********          ***                    */ 
+ /*              ******                                  */ 
+  0x06, 0x63, 0xb6, 0x01, 0x44, 0x98, 0x01, 0x25, 
+  0x8a, 0x01, 0x15, 0x7c, 0xdf, 0x48, 0x52, 0x5d, 
+  0xf4, 0x75, 0x45, 0xde, 0xf4, 0x74, 0x64, 0xde, 
+  0x46, 0x56, 0x4d, 0xe4, 0x64, 0x74, 0xde, 0x54, 
+  0x57, 0x4d, 0xf4, 0x35, 0x84, 0xdf, 0xc7, 0x50, 
+  0x11, 0xa8, 0x40, 0x13, 0x8a, 0x30, 0x14, 0x60, 
+  0x01, 0x19, 
+
+ /* Char 116 is 20px wide @ 3651 */
+ /*               ***************************            */ 
+ /*             ******************************           */ 
+ /*            *******************************           */ 
+ /*           ********************************           */ 
+ /*           ******              ****                   */ 
+ /*          *****                ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          *****                ****                   */ 
+ /*           ****                ****                   */ 
+ /*           ***                                        */ 
+  0x0d, 0x2d, 0xed, 0xa0, 0x12, 0xd8, 0x01, 0x3d, 
+  0x70, 0x14, 0xd7, 0x6d, 0x14, 0xde, 0x5d, 0x34, 
+  0xde, 0xe3, 0x4d, 0x44, 0xde, 0x5d, 0x34, 0xdf, 
+  0x4d, 0x34, 0xdf, 0x30, 0x83, 
+
+ /* Char 117 is 29px wide @ 3680 */
+ /*                 ******************                   */ 
+ /*               ********************                   */ 
+ /*             **********************                   */ 
+ /*            ***********************                   */ 
+ /*           *******                                    */ 
+ /*           *****                                      */ 
+ /*           ****                                       */ 
+ /*          *****                                       */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          *************************                   */ 
+ /*           ************************                   */ 
+ /*           ************************                   */ 
+ /*           ************************                   */ 
+  0x0d, 0x4d, 0x50, 0x14, 0xd7, 0x01, 0x2d, 0x90, 
+  0x11, 0xda, 0xdf, 0x70, 0x21, 0x50, 0x23, 0x40, 
+  0x23, 0x50, 0x23, 0xe6, 0x40, 0x24, 0xdc, 0xdf, 
+  0xe1, 0xdb, 0x00, 0x10, 0xa1, 
+
+ /* Char 118 is 25px wide @ 3709 */
+ /*                                 **                   */ 
+ /*                              *****                   */ 
+ /*                           ********                   */ 
+ /*                        ***********                   */ 
+ /*                     *************                    */ 
+ /*                  *************                       */ 
+ /*                ************                          */ 
+ /*             ************                             */ 
+ /*           ***********                                */ 
+ /*          **********                                  */ 
+ /*          *******                                     */ 
+ /*          *******                                     */ 
+ /*          **********                                  */ 
+ /*           ***********                                */ 
+ /*             ************                             */ 
+ /*                ************                          */ 
+ /*                  *************                       */ 
+ /*                     *************                    */ 
+ /*                        ***********                   */ 
+ /*                           ********                   */ 
+ /*                              *****                   */ 
+ /*                                 **                   */ 
+  0x04, 0x82, 0x02, 0x35, 0x02, 0x08, 0x01, 0xdb, 
+  0x01, 0xad, 0x00, 0x18, 0xd0, 0x01, 0x9c, 0x01, 
+  0x9c, 0x01, 0xab, 0x01, 0xca, 0x01, 0xef, 0x70, 
+  0x21, 0xa0, 0x1f, 0xb0, 0x1f, 0xc0, 0x1f, 0xc0, 
+  0x1e, 0xd0, 0x01, 0xed, 0x00, 0x1e, 0xb0, 0x20, 
+  0x80, 0x23, 0x50, 0x26, 0x20, 0x6e, 
+
+ /* Char 119 is 39px wide @ 3755 */
+ /*                                 **                   */ 
+ /*                              *****                   */ 
+ /*                           ********                   */ 
+ /*                        ***********                   */ 
+ /*                     *************                    */ 
+ /*                  ************                        */ 
+ /*                ***********                           */ 
+ /*              **********                              */ 
+ /*           **********                                 */ 
+ /*          ********                                    */ 
+ /*          ******                                      */ 
+ /*          *********                                   */ 
+ /*          ************                                */ 
+ /*            **************                            */ 
+ /*               ***************                        */ 
+ /*                   ***************                    */ 
+ /*                       ************                   */ 
+ /*                          *********                   */ 
+ /*                        ***********                   */ 
+ /*                    *************                     */ 
+ /*                 *************                        */ 
+ /*              *************                           */ 
+ /*            ************                              */ 
+ /*          ***********                                 */ 
+ /*          ********                                    */ 
+ /*          ******                                      */ 
+ /*          ********                                    */ 
+ /*           **********                                 */ 
+ /*             ***********                              */ 
+ /*                ***********                           */ 
+ /*                  ************                        */ 
+ /*                     *************                    */ 
+ /*                        ***********                   */ 
+ /*                           ********                   */ 
+ /*                              *****                   */ 
+ /*                                 **                   */ 
+  0x04, 0x82, 0x02, 0x35, 0x02, 0x08, 0x01, 0xdb, 
+  0x01, 0xad, 0x00, 0x18, 0xc0, 0x1a, 0xb0, 0x1b, 
+  0xa0, 0x1b, 0xa0, 0x1d, 0x80, 0x20, 0x60, 0x22, 
+  0x90, 0x1f, 0xc0, 0x1e, 0xd1, 0x01, 0xdd, 0x20, 
+  0x1d, 0xd2, 0x01, 0xdc, 0x01, 0xf9, 0x01, 0xdb, 
+  0x01, 0x9d, 0x00, 0x18, 0xd0, 0x01, 0x8d, 0x00, 
+  0x19, 0xc0, 0x1a, 0xb0, 0x1d, 0x80, 0x20, 0x60, 
+  0x22, 0x80, 0x21, 0xa0, 0x20, 0xb0, 0x20, 0xb0, 
+  0x1f, 0xc0, 0x1f, 0xd0, 0x01, 0xeb, 0x02, 0x08, 
+  0x02, 0x35, 0x02, 0x62, 0x06, 0xe1, 
+
+ /* Char 120 is 26px wide @ 3833 */
+ /*          *                       *                   */ 
+ /*          **                     **                   */ 
+ /*          ****                 ****                   */ 
+ /*          ******              *****                   */ 
+ /*          *******            ******                   */ 
+ /*           *******         *******                    */ 
+ /*             *******      *******                     */ 
+ /*              *******    ******                       */ 
+ /*                ****** *******                        */ 
+ /*                 ***********                          */ 
+ /*                  *********                           */ 
+ /*                   ********                           */ 
+ /*                  **********                          */ 
+ /*                 *************                        */ 
+ /*               *******  *******                       */ 
+ /*              ******      ******                      */ 
+ /*             ******        *******                    */ 
+ /*           *******          *******                   */ 
+ /*          *******             *****                   */ 
+ /*          *****                ****                   */ 
+ /*          ****                   **                   */ 
+ /*          **                      *                   */ 
+ /*          *                                           */ 
+  0x03, 0x11, 0xda, 0x1d, 0xe2, 0xd8, 0x2d, 0xe4, 
+  0xd4, 0x4d, 0xe6, 0xd1, 0x5d, 0xe7, 0xc6, 0xdf, 
+  0x79, 0x70, 0x13, 0x76, 0x70, 0x15, 0x74, 0x60, 
+  0x19, 0x61, 0x70, 0x1b, 0xb0, 0x1e, 0x90, 0x20, 
+  0x80, 0x1f, 0xa0, 0x1d, 0xd0, 0x01, 0x97, 0x27, 
+  0x01, 0x76, 0x66, 0x01, 0x56, 0x87, 0x01, 0x17, 
+  0xa7, 0xde, 0x7d, 0x05, 0xde, 0x5d, 0x34, 0xde, 
+  0x4d, 0x62, 0xde, 0x2d, 0x91, 0xde, 0x10, 0x86, 
+
+
+ /* Char 121 is 25px wide @ 3897 */
+ /*  **                                                  */ 
+ /* *****                            *                   */ 
+ /* ****                          ****                   */ 
+ /* ****                        ******                   */ 
+ /* ****                     *********                   */ 
+ /* ****                   **********                    */ 
+ /* ****                **********                       */ 
+ /* *****             **********                         */ 
+ /*  *****         **********                            */ 
+ /*   *****      *********                               */ 
+ /*   ******  *********                                  */ 
+ /*    **************                                    */ 
+ /*      **********                                      */ 
+ /*        **********                                    */ 
+ /*          ************                                */ 
+ /*             ************                             */ 
+ /*                ************                          */ 
+ /*                   ************                       */ 
+ /*                      ************                    */ 
+ /*                         **********                   */ 
+ /*                           ********                   */ 
+ /*                              *****                   */ 
+ /*                                 **                   */ 
+  0x12, 0x02, 0x55, 0xdf, 0x1d, 0x54, 0xdd, 0x4d, 
+  0x54, 0xdb, 0x6d, 0x54, 0xd8, 0x9d, 0x54, 0xd6, 
+  0xad, 0x64, 0xd3, 0xad, 0x95, 0xd0, 0xad, 0xc5, 
+  0x9a, 0x01, 0x15, 0x69, 0x01, 0x46, 0x29, 0x01, 
+  0x8d, 0x10, 0x1c, 0xa0, 0x20, 0xa0, 0x20, 0xc0, 
+  0x1f, 0xc0, 0x1f, 0xc0, 0x1f, 0xc0, 0x1f, 0xc0, 
+  0x1f, 0xa0, 0x20, 0x80, 0x23, 0x50, 0x26, 0x20, 
+  0x6e, 
+
+ /* Char 122 is 24px wide @ 3954 */
+ /*          ****                                        */ 
+ /*          *****                ****                   */ 
+ /*          *******              ****                   */ 
+ /*          ********             ****                   */ 
+ /*          **********           ****                   */ 
+ /*          ***********          ****                   */ 
+ /*          **** *******         ****                   */ 
+ /*          ****   ******        ****                   */ 
+ /*          ****    *******      ****                   */ 
+ /*          ****     *******     ****                   */ 
+ /*          ****       ******    ****                   */ 
+ /*          ****        ******   ****                   */ 
+ /*          ****         ******  ****                   */ 
+ /*          ****           ***** ****                   */ 
+ /*          ****            *********                   */ 
+ /*          ****             ********                   */ 
+ /*          ****              *******                   */ 
+ /*          ****               ******                   */ 
+ /*          ****                *****                   */ 
+  0x06, 0x54, 0x02, 0x45, 0xd3, 0x4d, 0xe7, 0xd1, 
+  0x4d, 0xe8, 0xd0, 0x4d, 0xea, 0xb4, 0xde, 0xba, 
+  0x4d, 0xe4, 0x17, 0x94, 0xde, 0x43, 0x68, 0x4d, 
+  0xe4, 0x47, 0x64, 0xde, 0x45, 0x75, 0x4d, 0xe4, 
+  0x76, 0x44, 0xde, 0x48, 0x63, 0x4d, 0xe4, 0x96, 
+  0x24, 0xde, 0x4b, 0x51, 0x4d, 0xe4, 0xc9, 0xde, 
+  0x4d, 0x08, 0xde, 0x4d, 0x17, 0xde, 0x4d, 0x26, 
+  0xde, 0x4d, 0x35, 0x0a, 0x21, 
+
+ /* Char 123 is 17px wide @ 4015 */
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                     ******                           */ 
+ /*                   **********                         */ 
+ /*     **************************************           */ 
+ /*    ******************** ********************         */ 
+ /*   ********************   ********************        */ 
+ /*  *******************       *******************       */ 
+ /*  *****                                   *****       */ 
+ /* *****                                     *****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+  0x07, 0x1f, 0x40, 0x23, 0x60, 0x20, 0xad, 0xf0, 
+  0x1a, 0xd0, 0xd7, 0x1d, 0x7a, 0xd7, 0x3d, 0x78, 
+  0xd6, 0x7d, 0x67, 0x50, 0x17, 0x56, 0x50, 0x19, 
+  0x55, 0x40, 0x1b, 0xe1, 0x40, 0x61, 
+
+ /* Char 124 is 15px wide @ 4045 */
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+ /* ***********************************************      */ 
+  0x0c, 0x40, 0x23, 0xe2, 0x00, 0x16, 0x51, 
+
+ /* Char 125 is 17px wide @ 4052 */
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* ****                                       ****      */ 
+ /* *****                                     *****      */ 
+ /*  *****                                   *****       */ 
+ /*  *******************       *******************       */ 
+ /*   ********************   ********************        */ 
+ /*    ******************** ********************         */ 
+ /*     **************************************           */ 
+ /*                    *********                         */ 
+ /*                     ******                           */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+  0x02, 0x84, 0x01, 0xbe, 0x14, 0x55, 0x01, 0x95, 
+  0x65, 0x01, 0x75, 0x7d, 0x67, 0xd6, 0x8d, 0x73, 
+  0xd7, 0xad, 0x71, 0xd7, 0xc0, 0x1a, 0x01, 0x19, 
+  0x02, 0x06, 0x02, 0x3f, 0x40, 0xab, 
+
+ /* Char 126 is 28px wide @ 4082 */
+ /*                      **                              */ 
+ /*                     *****                            */ 
+ /*                     ******                           */ 
+ /*                     *******                          */ 
+ /*                      *******                         */ 
+ /*                        *****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                         ****                         */ 
+ /*                        ****                          */ 
+ /*                        ****                          */ 
+ /*                       ****                           */ 
+ /*                      ****                            */ 
+ /*                      ****                            */ 
+ /*                     ****                             */ 
+ /*                     ****                             */ 
+ /*                     ****                             */ 
+ /*                     *****                            */ 
+ /*                     *******                          */ 
+ /*                      *******                         */ 
+ /*                       ******                         */ 
+ /*                        *****                         */ 
+ /*                          **                          */ 
+  0x07, 0x12, 0x02, 0x55, 0x02, 0x36, 0x02, 0x27, 
+  0x02, 0x27, 0x02, 0x35, 0x02, 0x4e, 0x14, 0x02, 
+  0x3f, 0x40, 0x23, 0x40, 0x23, 0xf4, 0x02, 0x3e, 
+  0x14, 0x02, 0x45, 0x02, 0x37, 0x02, 0x27, 0x02, 
+  0x26, 0x02, 0x35, 0x02, 0x52, 0x0a, 0x91, 
+
+ /* Char 196 is 33px wide @ 4121 */
+ /*          *                                           */ 
+ /*          ****                                        */ 
+ /*          ******                                      */ 
+ /*          *********                                   */ 
+ /*          ***********                                 */ 
+ /*             ***********                              */ 
+ /*               ***********                            */ 
+ /*                  ***********                         */ 
+ /*                  *************                  **   */ 
+ /*                  **** ***********              ****  */ 
+ /*                  ****   ***********           ****** */ 
+ /*                  ****      ***********        ****** */ 
+ /*                  ****        ***********       ****  */ 
+ /*                  ****           **********      **   */ 
+ /*                  ****             ********           */ 
+ /*                  ****               ******           */ 
+ /*                  ****              *******           */ 
+ /*                  ****           **********           */ 
+ /*                  ****         **********        **   */ 
+ /*                  ****       **********         ****  */ 
+ /*                  ****    **********           ****** */ 
+ /*                  ****  **********             ****** */ 
+ /*                  **************                ****  */ 
+ /*                  ************                   **   */ 
+ /*                 **********                           */ 
+ /*               **********                             */ 
+ /*             **********                               */ 
+ /*          **********                                  */ 
+ /*          ********                                    */ 
+ /*          ******                                      */ 
+ /*          ****                                        */ 
+ /*          *                                           */ 
+  0x91, 0x02, 0x74, 0x02, 0x46, 0x02, 0x29, 0x01, 
+  0xfb, 0x02, 0x0b, 0x01, 0xfb, 0x02, 0x0b, 0x01, 
+  0xdd, 0x0d, 0x52, 0xd6, 0x41, 0xbd, 0x14, 0xd5, 
+  0x43, 0xbb, 0x6d, 0x44, 0x6b, 0x86, 0xd4, 0x48, 
+  0xb7, 0x4d, 0x54, 0xba, 0x62, 0xd6, 0x4d, 0x08, 
+  0xde, 0x4d, 0x26, 0xde, 0x4d, 0x17, 0xde, 0x4b, 
+  0xad, 0xe4, 0x9a, 0x82, 0xd6, 0x47, 0xa9, 0x4d, 
+  0x54, 0x4a, 0xb6, 0xd4, 0x42, 0xad, 0x06, 0xd4, 
+  0xd1, 0xd3, 0x4d, 0x5c, 0xd6, 0x2d, 0x5a, 0x01, 
+  0xca, 0x01, 0xca, 0x01, 0xba, 0x01, 0xe8, 0x02, 
+  0x06, 0x02, 0x24, 0x02, 0x41, 0x05, 0x21, 
+
+ /* Char 214 is 39px wide @ 4208 */
+ /*                      *********                       */ 
+ /*                   ***************                    */ 
+ /*                 *******************                  */ 
+ /*               ***********************                */ 
+ /*              **********     **********               */ 
+ /*             *******             *******              */ 
+ /*             ******               ******              */ 
+ /*            *****                   *****        **   */ 
+ /*            ****                     ****       ****  */ 
+ /*           *****                     *****     ****** */ 
+ /*           ****                       ****     ****** */ 
+ /*          *****                       *****     ****  */ 
+ /*          *****                       *****      **   */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****           */ 
+ /*          ****                         ****      **   */ 
+ /*          *****                       *****     ****  */ 
+ /*          *****                       *****    ****** */ 
+ /*           ****                       ****     ****** */ 
+ /*           *****                     *****      ****  */ 
+ /*           *****                     *****       **   */ 
+ /*            *****                   *****             */ 
+ /*             ******               ******              */ 
+ /*             *******             *******              */ 
+ /*              **********     **********               */ 
+ /*               ***********************                */ 
+ /*                 *******************                  */ 
+ /*                   ***************                    */ 
+ /*                      *********                       */ 
+  0x0a, 0x59, 0x01, 0xcd, 0x20, 0x17, 0xd6, 0x01, 
+  0x3d, 0xad, 0xfa, 0x5a, 0xdd, 0x7d, 0x07, 0xdc, 
+  0x6d, 0x26, 0xdb, 0x5d, 0x65, 0x82, 0xd0, 0x4d, 
+  0x84, 0x74, 0xb5, 0xd8, 0x55, 0x6a, 0x4d, 0xa4, 
+  0x56, 0x95, 0xda, 0x55, 0x4a, 0x5d, 0xa5, 0x62, 
+  0xbe, 0x24, 0xdc, 0x4d, 0x64, 0xdc, 0x46, 0x2b, 
+  0x5d, 0xa5, 0x54, 0xa5, 0xda, 0x54, 0x6a, 0x4d, 
+  0xa4, 0x56, 0xa5, 0xd8, 0x56, 0x4b, 0x5d, 0x85, 
+  0x72, 0xd0, 0x5d, 0x65, 0xdb, 0x6d, 0x26, 0xdc, 
+  0x7d, 0x07, 0xdd, 0xa5, 0xad, 0xfd, 0xa0, 0x13, 
+  0xd6, 0x01, 0x7d, 0x20, 0x1c, 0x90, 0x01, 0x0e, 
+
+
+ /* Char 220 is 34px wide @ 4296 */
+ /*                   ************************           */ 
+ /*                ***************************           */ 
+ /*              *****************************           */ 
+ /*             ******************************           */ 
+ /*             *******                                  */ 
+ /*            ******                               **   */ 
+ /*           *****                                ****  */ 
+ /*           *****                               ****** */ 
+ /*           ****                                ****** */ 
+ /*          *****                                 ****  */ 
+ /*          ****                                   **   */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          *****                                  **   */ 
+ /*           ****                                 ****  */ 
+ /*           *****                               ****** */ 
+ /*           *****                               ****** */ 
+ /*            ******                              ****  */ 
+ /*             *******                             **   */ 
+ /*             ******************************           */ 
+ /*              *****************************           */ 
+ /*                ***************************           */ 
+ /*                   ************************           */ 
+  0x0d, 0x6d, 0xbd, 0xcd, 0xed, 0xa0, 0x11, 0xd9, 
+  0x01, 0x2d, 0x97, 0x02, 0x06, 0x01, 0x32, 0xc5, 
+  0x01, 0x44, 0xb5, 0x01, 0x36, 0xa4, 0x01, 0x46, 
+  0x95, 0x01, 0x54, 0xa4, 0x01, 0x72, 0xbe, 0x24, 
+  0x02, 0x45, 0x01, 0x62, 0xc4, 0x01, 0x54, 0xbf, 
+  0x50, 0x13, 0x6b, 0x60, 0x12, 0x4d, 0x07, 0x01, 
+  0x12, 0xd1, 0x01, 0x2d, 0xa0, 0x11, 0xdc, 0xde, 
+  0xdf, 0xdb, 0x00, 0x10, 0x21, 
+
+ /* Char 223 is 31px wide @ 4357 */
+ /*          ******************************              */ 
+ /*          ********************************            */ 
+ /*          **********************************          */ 
+ /*          ***********************************         */ 
+ /*                                       ******         */ 
+ /*                                         *****        */ 
+ /*                                          ****        */ 
+ /*                                          *****       */ 
+ /*           ***                             ****       */ 
+ /*           ****           *****            ****       */ 
+ /*          *****          *******           ****       */ 
+ /*          *****          ********          ****       */ 
+ /*          ****          **********         ****       */ 
+ /*          ****         *****  *****       *****       */ 
+ /*          ****         ****     ****      *****       */ 
+ /*          ****         ****      ****    *****        */ 
+ /*          ****        ****        ************        */ 
+ /*          ****        ****         **********         */ 
+ /*          *****      ****           ********          */ 
+ /*           *****    *****            *****            */ 
+ /*           *************                              */ 
+ /*            ************                              */ 
+ /*             *********                                */ 
+ /*               ******                                 */ 
+  0x0c, 0xd0, 0x12, 0xd9, 0x01, 0x4d, 0x70, 0x16, 
+  0xd5, 0x01, 0x70, 0x22, 0x60, 0x24, 0x50, 0x24, 
+  0x40, 0x24, 0x5d, 0x33, 0x01, 0x14, 0xd3, 0x4b, 
+  0x5c, 0x4d, 0x25, 0xa7, 0xb4, 0xd2, 0x5a, 0x8a, 
+  0x4d, 0x24, 0xaa, 0x94, 0xd2, 0x49, 0x52, 0x57, 
+  0x5d, 0x24, 0x94, 0x54, 0x65, 0xd2, 0x49, 0x46, 
+  0x44, 0x5d, 0x34, 0x84, 0x8c, 0xd3, 0x48, 0x49, 
+  0xad, 0x45, 0x64, 0xb8, 0xd6, 0x54, 0x5c, 0x5d, 
+  0x8d, 0x00, 0x1c, 0xc0, 0x1d, 0x90, 0x21, 0x60, 
+  0xb0, 
+
+ /* Char 228 is 26px wide @ 4430 */
+ /*               ******                                 */ 
+ /*             **********                               */ 
+ /*            ************                  **          */ 
+ /*           *************      ****       ****         */ 
+ /*           *****   ******     ****      ******        */ 
+ /*          *****      ****      ****     ******        */ 
+ /*          *****      *****     ****      ****         */ 
+ /*          ****        ****     ****       **          */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****     ****                   */ 
+ /*          ****        ****    *****       **          */ 
+ /*          ****        ****    ****       ****         */ 
+ /*          ****       *****  ******      ******        */ 
+ /*          ************************      ******        */ 
+ /*           **********************        ****         */ 
+ /*           *********************          **          */ 
+ /*           *******************                        */ 
+  0x06, 0xa6, 0x02, 0x0a, 0x01, 0xdc, 0xd5, 0x2d, 
+  0x6d, 0x06, 0x47, 0x4d, 0x55, 0x36, 0x54, 0x66, 
+  0xd3, 0x56, 0x46, 0x45, 0x6d, 0x35, 0x65, 0x54, 
+  0x64, 0xd4, 0x48, 0x45, 0x47, 0x2d, 0x5e, 0x24, 
+  0x84, 0x54, 0xde, 0x48, 0x44, 0x57, 0x2d, 0x54, 
+  0x84, 0x44, 0x74, 0xd4, 0x47, 0x52, 0x66, 0x6d, 
+  0x3d, 0xb6, 0x6d, 0x4d, 0x98, 0x4d, 0x5d, 0x8a, 
+  0x2d, 0x6d, 0x60, 0x01, 0x0f, 
+
+ /* Char 246 is 30px wide @ 4491 */
+ /*                   *******                            */ 
+ /*                *************                         */ 
+ /*              *****************                       */ 
+ /*             *******************          **          */ 
+ /*            *******       *******        ****         */ 
+ /*            *****           *****       ******        */ 
+ /*           *****             *****      ******        */ 
+ /*           ****               ****       ****         */ 
+ /*          *****               *****       **          */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          ****                 ****                   */ 
+ /*          *****               *****       **          */ 
+ /*           ****               ****       ****         */ 
+ /*           *****             *****      ******        */ 
+ /*            *****           *****       ******        */ 
+ /*            *******       *******        ****         */ 
+ /*             *******************          **          */ 
+ /*              *****************                       */ 
+ /*                *************                         */ 
+ /*                   *******                            */ 
+  0x0a, 0x27, 0x01, 0xed, 0x00, 0x19, 0xd4, 0x01, 
+  0x6d, 0x6a, 0x2d, 0x77, 0x77, 0x84, 0xd6, 0x5b, 
+  0x57, 0x6d, 0x45, 0xd0, 0x56, 0x6d, 0x44, 0xd2, 
+  0x47, 0x4d, 0x45, 0xd2, 0x57, 0x2d, 0x5e, 0x24, 
+  0xd4, 0x4d, 0xe5, 0xd2, 0x57, 0x2d, 0x64, 0xd2, 
+  0x47, 0x4d, 0x55, 0xd0, 0x56, 0x6d, 0x55, 0xb5, 
+  0x76, 0xd5, 0x77, 0x78, 0x4d, 0x7d, 0x6a, 0x2d, 
+  0x9d, 0x40, 0x19, 0xd0, 0x01, 0xe7, 0x00, 0x11, 
+  0x31, 
+
+ /* Char 252 is 29px wide @ 4556 */
+ /*                 ******************                   */ 
+ /*               ********************                   */ 
+ /*             **********************       **          */ 
+ /*            ***********************      ****         */ 
+ /*           *******                      ******        */ 
+ /*           *****                        ******        */ 
+ /*           ****                          ****         */ 
+ /*          *****                           **          */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                                        */ 
+ /*          ****                            **          */ 
+ /*          ****                           ****         */ 
+ /*          ****                          ******        */ 
+ /*          ****                          ******        */ 
+ /*          *************************      ****         */ 
+ /*           ************************       **          */ 
+ /*           ************************                   */ 
+ /*           ************************                   */ 
+  0x0d, 0x4d, 0x50, 0x14, 0xd7, 0x01, 0x2d, 0x97, 
+  0x2d, 0x7d, 0xa6, 0x4d, 0x57, 0xd9, 0x6d, 0x45, 
+  0xdb, 0x6d, 0x44, 0xdd, 0x4d, 0x45, 0xde, 0x2d, 
+  0x5e, 0x24, 0x02, 0x44, 0xdf, 0x2d, 0x54, 0xde, 
+  0x4d, 0x4f, 0x4d, 0xd6, 0xd3, 0xdc, 0x64, 0xd5, 
+  0xdb, 0x72, 0xd6, 0xfd, 0xb0, 0x01, 0x0a, 
+
+ /* Char 8364 is 28px wide @ 4603 */
+ /*                     ***     ***                      */ 
+ /*                     ***     ***                      */ 
+ /*                     ***     ***                      */ 
+ /*                     ***     ***                      */ 
+ /*                     ***********                      */ 
+ /*                 ******************                   */ 
+ /*               **********************                 */ 
+ /*              *************************               */ 
+ /*             ***********     ***********              */ 
+ /*            ******   ***     ***   ******             */ 
+ /*            *****    ***     ***    *****             */ 
+ /*           *****     ***     ***     *****            */ 
+ /*           ****      ***     ***      ****            */ 
+ /*          *****      ***     ***      *****           */ 
+ /*          ****       ***     ***       ****           */ 
+ /*          ****       ***     ***       ****           */ 
+ /*          ****       ***     ***       ****           */ 
+ /*          ****       ***     ***       ****           */ 
+ /*          ****               ***       ****           */ 
+ /*          ****               ***       ****           */ 
+ /*          ****                        *****           */ 
+ /*          *****                       ****            */ 
+ /*           ****                         **            */ 
+ /*           ***                                        */ 
+  0x07, 0x0e, 0x23, 0x53, 0x01, 0xdb, 0x01, 0x9d, 
+  0x50, 0x14, 0xd9, 0x01, 0x1d, 0xcd, 0xdb, 0x5b, 
+  0xdb, 0x63, 0x35, 0x33, 0x6d, 0xa5, 0x43, 0x53, 
+  0x45, 0xd9, 0x55, 0x35, 0x35, 0x5d, 0x84, 0x63, 
+  0x53, 0x64, 0xd7, 0x56, 0x35, 0x36, 0x5d, 0x6e, 
+  0x24, 0x73, 0x53, 0x74, 0xd6, 0xf4, 0xd2, 0x37, 
+  0x4d, 0x64, 0xdb, 0x5d, 0x65, 0xda, 0x4d, 0x84, 
+  0xdc, 0x2d, 0x83, 0x08, 0x31, 
+
+};
+
+/* Character descriptors */
+const FONT_CHAR_INFO Ubuntu36ptLengths[] = {
+ { 3}, /*   */
+ {16}, /* ! */
+ {16}, /* " */
+ {69}, /* # */
+ {66}, /* $ */
+ {108}, /* % */
+ {88}, /* & */
+ { 8}, /* ' */
+ {32}, /* ( */
+ {33}, /* ) */
+ {53}, /* * */
+ {11}, /* + */
+ {15}, /* , */
+ { 5}, /* - */
+ {12}, /* . */
+ {40}, /* / */
+ {58}, /* 0 */
+ {20}, /* 1 */
+ {72}, /* 2 */
+ {57}, /* 3 */
+ {49}, /* 4 */
+ {57}, /* 5 */
+ {71}, /* 6 */
+ {49}, /* 7 */
+ {67}, /* 8 */
+ {66}, /* 9 */
+ {19}, /* : */
+ {22}, /* ; */
+ {51}, /* < */
+ { 7}, /* = */
+ {51}, /* > */
+ {44}, /* ? */
+ {117}, /* @ */
+ {78}, /* A */
+ {47}, /* B */
+ {61}, /* C */
+ {49}, /* D */
+ {15}, /* E */
+ {12}, /* F */
+ {54}, /* G */
+ {15}, /* H */
+ { 7}, /* I */
+ {33}, /* J */
+ {66}, /* K */
+ { 8}, /* L */
+ {69}, /* M */
+ {53}, /* N */
+ {71}, /* O */
+ {37}, /* P */
+ {95}, /* Q */
+ {49}, /* R */
+ {70}, /* S */
+ {11}, /* T */
+ {45}, /* U */
+ {60}, /* V */
+ {93}, /* W */
+ {79}, /* X */
+ {58}, /* Y */
+ {84}, /* Z */
+ {10}, /* [ */
+ {42}, /* \ */
+ {10}, /* ] */
+ {48}, /* ^ */
+ { 5}, /* _ */
+ {21}, /* ` */
+ {48}, /* a */
+ {46}, /* b */
+ {41}, /* c */
+ {44}, /* d */
+ {60}, /* e */
+ {28}, /* f */
+ {62}, /* g */
+ {32}, /* h */
+ {13}, /* i */
+ {24}, /* j */
+ {49}, /* k */
+ {16}, /* l */
+ {42}, /* m */
+ {29}, /* n */
+ {57}, /* o */
+ {44}, /* p */
+ {45}, /* q */
+ {14}, /* r */
+ {50}, /* s */
+ {29}, /* t */
+ {29}, /* u */
+ {46}, /* v */
+ {78}, /* w */
+ {64}, /* x */
+ {57}, /* y */
+ {61}, /* z */
+ {30}, /* { */
+ { 7}, /* | */
+ {30}, /* } */
+ {39}, /* ~ */
+ {87}, /* Ä */
+ {88}, /* Ö */
+ {61}, /* Ü */
+ {73}, /* ß */
+ {61}, /* ä */
+ {65}, /* ö */
+ {47}, /* ü */
+ {61}, /* € */
+};
+
+const uint16_t Ubuntu36ptExtra[] = {
+196,214,220,223,228,246,252,8364,65535
+};
+
+/* Font info */
+const struct FONT_DEF Font_Ubuntu36pt = {
+         1,   /* width (1 == comressed) */
+        52,   /* character height */
+        32,   /* first char */
+       126,   /* last char */
+    Ubuntu36ptBitmaps, Ubuntu36ptLengths, Ubuntu36ptExtra
+};
+
+/* Font metadata: 
+ * Name:          Ubuntu Regular 36pt
+ * Height:        52 px (7 bytes)
+ * Maximum width: 47 px
+ * Storage size:  4767 bytes (compressed by 75%)
+ */
diff --git a/lcd/fonts/ubuntu36.h b/lcd/fonts/ubuntu36.h
new file mode 100644 (file)
index 0000000..0c92f54
--- /dev/null
@@ -0,0 +1,3 @@
+#include "lcd/fonts.h"
+
+extern const struct FONT_DEF Font_Ubuntu36pt;
diff --git a/main.c b/main.c
index 80c0e8e..d0dfce7 100644 (file)
--- a/main.c
+++ b/main.c
 #include "projectconfig.h"
 #include "sysinit.h"
 
+#include "core/adc/adc.h"
+#include "core/cpu/cpu.h"
+#include "core/pmu/pmu.h"
 #include "core/gpio/gpio.h"
 #include "core/systick/systick.h"
+#include "core/usbhid-rom/usbmsc.h"
 
 #ifdef CFG_INTERFACE
   #include "core/cmd/cmd.h"
 #endif
 
+#include "lcd/display.h"
+
+#include "r0ketports.h"
+
+uint8_t getInputRaw(void) {
+    uint8_t result = BTN_NONE;
+
+    if (gpioGetValue(RB_BTN3)==0) {
+        result |= BTN_UP;
+    }
+
+    if (gpioGetValue(RB_BTN2)==0) {
+        result |= BTN_DOWN;
+    }
+
+    if (gpioGetValue(RB_BTN4)==0) {
+        result |= BTN_ENTER;
+    }
+
+    if (gpioGetValue(RB_BTN0)==0) {
+        result |= BTN_LEFT;
+    }
+
+    if (gpioGetValue(RB_BTN1)==0) {
+        result |= BTN_RIGHT;
+    }
+
+    return result;
+}
+
+void backlightInit(void) {
+  /* Enable the clock for CT16B1 */
+  SCB_SYSAHBCLKCTRL |= (SCB_SYSAHBCLKCTRL_CT16B1);
+
+  /* Configure PIO1.9 as Timer1_16 MAT0 Output */
+  IOCON_PIO1_9 &= ~IOCON_PIO1_9_FUNC_MASK;
+  IOCON_PIO1_9 |= IOCON_PIO1_9_FUNC_CT16B1_MAT0;
+
+  /* Set default duty cycle (MR1) */
+  TMR_TMR16B1MR0 = 0; //(0xFFFF * (100 - brightness)) / 100;
+
+  /* External Match Register Settings for PWM */
+  TMR_TMR16B1EMR = TMR_TMR16B1EMR_EMC0_TOGGLE | TMR_TMR16B1EMR_EM0;
+
+  /* enable Timer1 */
+  TMR_TMR16B1TCR = TMR_TMR16B1TCR_COUNTERENABLE_ENABLED;
+
+  /* Enable PWM0 */
+  TMR_TMR16B1PWMC = TMR_TMR16B1PWMC_PWM0_ENABLED;
+  // Enable Step-UP
+  gpioSetDir(RB_PWR_LCDBL, gpioDirection_Output);
+  gpioSetValue(RB_PWR_LCDBL, 0);
+}
+
+
+
+void rbInit() {
+    // TODO FIXME special port disable ? LEDs BTNs ?
+
+    // prepare power
+    // TODO FIXME more power init needed ? chrg + volt input ?
+    // enable external vcc
+    gpioSetDir(RB_PWR_GOOD, gpioDirection_Output);
+    gpioSetValue (RB_PWR_GOOD, 0); 
+
+    // Disable USB Connect (we don't want USB by default)
+    gpioSetDir(USB_CONNECT, gpioDirection_Output);
+    gpioSetValue(USB_CONNECT, 1);
+
+    static uint8_t ports[] = { RB_BTN0, RB_BTN1, RB_BTN2, RB_BTN3, RB_BTN4,
+                        RB_LED0, RB_LED1, RB_LED2, 
+                        RB_SPI_SS0, RB_SPI_SS1, RB_SPI_SS2,
+                        RB_SPI_SS3, RB_SPI_SS4, RB_SPI_SS5,
+                        RB_HB0, RB_HB1, RB_HB2,
+                        RB_HB3, RB_HB4, RB_HB5};
+
+    volatile uint32_t * regs[] = {&RB_BTN0_IO, &RB_BTN1_IO, &RB_BTN2_IO,
+                                  &RB_BTN3_IO, &RB_BTN4_IO};
+
+    int i = 0;
+    while( i<10 ){
+        gpioSetDir(ports[i], ports[i+1], gpioDirection_Input);
+        gpioSetPullup(regs[i/2], gpioPullupMode_PullUp);
+        i+=2;
+    }
+
+    // prepate chrg_stat
+    gpioSetDir(RB_PWR_CHRG, gpioDirection_Input);
+    gpioSetPullup (&RB_PWR_CHRG_IO, gpioPullupMode_PullUp);
+
+    gpioSetDir(RB_LED3, gpioDirection_Input);
+    IOCON_PIO1_11 = 0x41;
+
+    // prepare LEDs
+    IOCON_JTAG_TDI_PIO0_11 &= ~IOCON_JTAG_TDI_PIO0_11_FUNC_MASK;
+    IOCON_JTAG_TDI_PIO0_11 |= IOCON_JTAG_TDI_PIO0_11_FUNC_GPIO; 
+
+    while( i<16 ){
+        gpioSetDir(ports[i],ports[i+1], gpioDirection_Output);
+        gpioSetValue (ports[i], ports[i+1], 0);
+        i+=2;
+    }
+
+    // Set LED3 to ?
+    IOCON_PIO1_11 = 0x41;
+
+    // prepare lcd
+    // TODO FIXME more init needed ?
+    gpioSetDir(RB_LCD_BL, gpioDirection_Output);
+    gpioSetValue (RB_LCD_BL, 0); 
+
+    // Set P0.0 to GPIO
+    RB_PWR_LCDBL_IO&= ~RB_PWR_LCDBL_IO_FUNC_MASK;
+    RB_PWR_LCDBL_IO|= RB_PWR_LCDBL_IO_FUNC_GPIO; 
+    gpioSetDir(RB_PWR_LCDBL, gpioDirection_Input);
+    gpioSetPullup(&RB_PWR_LCDBL_IO, gpioPullupMode_Inactive);
+
+    // prepare SPI/SS
+    // TODO FIXME init miso/mosi/sck somehow ? 
+    // prepare hackerbus
+    while(i<sizeof(ports)){
+        gpioSetDir(ports[i],ports[i+1], gpioDirection_Output);
+        gpioSetValue (ports[i], ports[i+1], 1);
+        i+=2;
+    }
+
+    backlightInit();
+    //font=&Font_7x8;
+}
+
+
 /**************************************************************************/
 /*! 
     Main program entry point.  After reset, normal code execution will
 int main(void)
 {
   // Configure cpu and mandatory peripherals
-  systemInit();
-
-  uint32_t currentSecond, lastSecond;
-  currentSecond = lastSecond = 0;
-  
-  while (1)
-  {
-    // Toggle LED once per second
-    currentSecond = systickGetSecondsActive();
-    if (currentSecond != lastSecond)
+  //systemInit();
+
+  cpuInit();
+  systickInit(CFG_SYSTICK_DELAY_IN_MS);
+  //gpioInit();
+  // pmuInit();
+  //  adcInit();
+  rbInit();
+
+  badge_display_init();
+  gpioSetDir(0, 11, gpioDirection_Output);
+
+
+  badge_framebuffer fb = { 
     {
-      lastSecond = currentSecond;
-      gpioSetValue(CFG_LED_PORT, CFG_LED_PIN, lastSecond % 2);
+      {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }, {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }, {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }, {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }, {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }, {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }, {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }, {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }, {
+       1,   2,  3,  4,  5,  6,  7,  8,  9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20,
+       21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40,
+       41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+       61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80,
+       81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96
+      }
     }
+  };
+
+  badge_framebuffer_flush(&fb);
+
+  usbMSCInit();
+  for(;;);
 
-    // Poll for CLI input if CFG_INTERFACE is enabled in projectconfig.h
-    #ifdef CFG_INTERFACE 
-      cmdPoll(); 
-    #endif
+  for(uint8_t i = 0; ; ++i) {
+    gpioSetValue(0, 11, i & 1);
+    systickDelay(500);
   }
 
   return 0;
index b0bf5be..de7d9c6 100644 (file)
         LPC1343 LPCXpresso board
 
     -----------------------------------------------------------------------*/
-    #define CFG_BRD_LPC1343_REFDESIGN
-    // #define CFG_BRD_LPC1343_REFDESIGN_MINIMAL
+// #define CFG_BRD_LPC1343_REFDESIGN
+#define CFG_BRD_LPC1343_REFDESIGN_MINIMAL
     // #define CFG_BRD_LPC1343_TFTLCDSTANDALONE_USB
     // #define CFG_BRD_LPC1343_TFTLCDSTANDALONE_UART
     // #define CFG_BRD_LPC1343_802154USBSTICK
                               CDC (see 'puts' in systeminit.c).
 
     -----------------------------------------------------------------------*/
+#define CFG_USBMSC (1)
+
+
     #define CFG_USB_VID                   (0x239A)
     #define CFG_USB_PID                   (0x1002)
        
diff --git a/r0ketports.h b/r0ketports.h
new file mode 100644 (file)
index 0000000..1b753f6
--- /dev/null
@@ -0,0 +1,130 @@
+#ifndef INCLUDED_R0KET_PORTS_H
+#define INCLUDED_R0KET_PORTS_H
+
+// LED
+#define RB_LED0                        0,11
+
+#define RB_LED1                        1,7
+
+#define RB_LED2                        1,6
+
+#define RB_LED3                        1,11
+
+
+// Infrared
+//#define RB_IROUT             1,5
+
+//#define RB_IRIN                      1,8
+//#define RB_IRIN_IO           IOCON_PIO1_8
+
+
+// Buttons
+#define RB_BTN0                        0,1
+#define RB_BTN0_IO             IOCON_PIO0_1
+
+#define RB_BTN1                        2,9
+#define RB_BTN1_IO             IOCON_PIO2_9
+
+#define RB_BTN2                        2,6
+#define RB_BTN2_IO             IOCON_PIO2_6
+
+#define RB_BTN3                        3,3
+#define RB_BTN3_IO             IOCON_PIO3_3
+
+#define RB_BTN4                        2,7
+#define RB_BTN4_IO             IOCON_PIO2_7
+
+
+// LCD
+#define RB_LCD_BL              1,9
+
+#define RB_LCD_CS              2,1
+
+#define RB_LCD_RST             2,2
+
+
+// I2C
+#define RB_I2C_SCL             0,4
+
+#define RB_I2C_SCA             0,5
+
+
+// SPI
+#define RB_SPI_MISO            0,8
+
+#define RB_SPI_MOSI            0,9
+
+#define RB_SPI_SCK             2,11
+
+#define RB_SPI_CS_DF   2,0
+
+#define RB_SPI_SS0             2,5
+
+#define RB_SPI_SS1             2,4
+
+#define RB_SPI_SS2             2,8
+
+#define RB_SPI_SS3             3,2
+
+#define RB_SPI_SS4             3,1
+
+#define RB_SPI_SS5             2,10
+
+
+// Power
+#define RB_PWR_VOLT            1,0
+
+#define RB_PWR_GOOD            1,8
+
+#define RB_PWR_CHRG            2,3
+#define RB_PWR_CHRG_IO IOCON_PIO2_3
+
+#define RB_PWR_LCDBL    0,0
+#define RB_PWR_LCDBL_IO IOCON_nRESET_PIO0_0
+#define RB_PWR_LCDBL_IO_FUNC_MASK IOCON_nRESET_PIO0_0_FUNC_MASK
+#define RB_PWR_LCDBL_IO_FUNC_GPIO IOCON_nRESET_PIO0_0_FUNC_GPIO
+
+// Hackerbus
+#define RB_HB0                 1,3
+#define RB_HB0_IO              IOCON_PIO1_3
+
+#define RB_HB1                 0,10
+#define RB_HB1_IO              IOCON_PIO0_10
+
+#define RB_HB2                 1,1
+#define RB_HB2_IO              IOCON_PIO1_1
+
+#define RB_HB3                 0,2
+#define RB_HB3_IO              IOCON_PIO0_2
+
+#define RB_HB4                 1,4
+#define RB_HB4_IO              IOCON_PIO1_4
+
+#define RB_HB5                 1,2
+#define RB_HB5_IO              IOCON_PIO1_2
+
+// Funk
+#define RB_NRF_CE              1,5
+#define RB_NRF_CE_IO           IOCON_PIO1_5
+#define RB_SPI_NRF_CS          1,10
+#define RB_SPI_NRF_CS_IO       IOCON_PIO1_10
+
+// Misc
+#define RB_BUSINT              3,0
+#define RB_BUSINT_IO           IOCON_PIO3_0
+
+#define RB_USB_VBUS            0,3
+
+#define RB_EEPROM_ADDR                 0xA0
+
+#define USB_CONNECT 0,6
+
+
+#define BTN_NONE 0
+#define BTN_UP   (1<<0)
+#define BTN_DOWN (1<<1)
+#define BTN_LEFT (1<<2)
+#define BTN_RIGHT (1<<3)
+#define BTN_ENTER (1<<4)
+
+#endif
This page took 0.328346 seconds and 4 git commands to generate.