diff --git a/Arduino/BTCDieselHeater/BTCDieselHeater.ino b/Arduino/BTCDieselHeater/BTCDieselHeater.ino deleted file mode 100644 index baa3a6f..0000000 --- a/Arduino/BTCDieselHeater/BTCDieselHeater.ino +++ /dev/null @@ -1,905 +0,0 @@ -/* - * This file is part of the "bluetoothheater" distribution - * (https://gitlab.com/mrjones.id.au/bluetoothheater) - * - * Copyright (C) 2018 Ray Jones - * Copyright (C) 2018 James Clark - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - - /* - Chinese Heater Half Duplex Serial Data Sending Tool - - Connects to the blue wire of a Chinese heater, which is the half duplex serial link. - Sends and receives data from hardware serial port 1. - - Terminology: Tx is to the heater unit, Rx is from the heater unit. - - Typical data frame timing on the blue wire is: - __Tx_Rx____________________________Tx_Rx____________________________Tx_Rx___________ - - This software can connect to the blue wire in a normal OEM system, detecting the - OEM controller and allowing extraction of the data or injecting on/off commands. - - If Pin 21 is grounded on the Due, this simple stream will be reported over Serial and - no control from the Arduino will be allowed. - This allows passive sniffing of the blue wire in a normal system. - - The binary data is received from the line. - If it has been > 100ms since the last blue wire activity this indicates a new frame - sequence is starting from the OEM controller. - Synchronise as such then count off the next 24 bytes storing them in the Controller's - data array. These bytes are then reported over Serial to the PC in ASCII. - - It is then expected the heater will respond with it's 24 bytes. - Capture those bytes and store them in the Heater1 data array. - Once again these bytes are then reported over Serial to the PC in ASCII. - - If no activity is sensed in a second, it is assumed no OEM controller is attached and we - have full control over the heater. - - Either way we can now inject a message onto the blue wire allowing our custom - on/off control. - We must remain synchronous with an OEM controller if it exists otherwise E-07 - faults will be caused. - - Typical data frame timing on the blue wire is then: - __OEMTx_HtrRx__OurTx_HtrRx____________OEMTx_HtrRx__OurTx_HtrRx____________OEMTx_HtrRx__OurTx_HtrRx_________ - - The second HtrRx to the next OEMTx delay is always > 100ms and is paced by the OEM controller. - The delay before seeing Heater Rx data after any Tx is usually much less than 10ms. - But this does rise if new max/min or voltage settings are sent. - **The heater only ever sends Rx data in response to a data frame from a controller** - - For Bluetooth connectivity, a HC-05 Bluetooth module is attached to Serial2: - TXD -> Rx2 (pin 17) - RXD -> Tx2 (pin 16) - EN(key) -> pin 15 - STATE -> pin 4 - - - This code only works with boards that have more than one hardware serial port like Arduino - Mega, Due, Zero, ESP32 etc. - - - The circuit: - - a Tx Rx multiplexer is required to combine the Arduino's Tx1 And Rx1 pins onto the blue wire. - - a Tx Enable signal from pin 22 controls the multiplexer, high for Tx, low for Rx - - Serial logging software on Serial0 via USB link - - created 23 Sep 2018 by Ray Jones - - This example code is in the public domain. -*/ - -#include "BTCWebServer.h" -#include "Protocol.h" -#include "TxManage.h" -#include "pins.h" -#include "NVStorage.h" -#include "debugport.h" -#include "SmartError.h" -#include "BTCWifi.h" -#include "BTCConfig.h" -#include "UtilClasses.h" -#include "BTCota.h" -#include "BTCWebServer.h" -#include "ScreenManager.h" -#include -#include -#include "keypad.h" -#include "helpers.h" -#include "Wire.h" -#include "Clock.h" -#include "BTC_JSON.h" - -#define FAILEDSSID "BTCESP32" -#define FAILEDPASSWORD "thereisnospoon" - -#define RX_DATA_TIMOUT 50 - - - -#ifdef ESP32 -#include "BluetoothESP32.h" -#else -#include "BluetoothHC05.h" -#endif - -// Setup Serial Port Definitions -#if defined(__arm__) -// Required for Arduino Due, UARTclass is derived from HardwareSerial -static UARTClass& BlueWireSerial(Serial1); -#else -// for ESP32, Mega -// HardwareSerial is it for these boards -static HardwareSerial& BlueWireSerial(Serial1); -#endif - -void initBlueWireSerial(); -bool validateFrame(const CProtocol& frame, const char* name); -void checkDisplayUpdate(); -void checkDebugCommands(); -void updateJsonBT(); - -// DS18B20 temperature sensor support -OneWire ds(DS18B20_Pin); // on pin 5 (a 4.7K resistor is necessary) -DallasTemperature TempSensor(&ds); -long lastTemperatureTime; // used to moderate DS18B20 access -float fFilteredTemperature = -100; // -100: force direct update uopn first pass -const float fAlpha = 0.95; // exponential mean alpha - -unsigned long lastAnimationTime; // used to sequence updates to LCD for animation - -CommStates CommState; -CTxManage TxManage(TxEnbPin, BlueWireSerial); -CModeratedFrame OEMCtrlFrame; // data packet received from heater in response to OEM controller packet -CModeratedFrame HeaterFrame1; // data packet received from heater in response to OEM controller packet -CProtocol HeaterFrame2; // data packet received from heater in response to our packet -CProtocol DefaultBTCParams(CProtocol::CtrlMode); // defines the default parameters, used in case of no OEM controller -CSmartError SmartError; -CKeyPad KeyPad; -CScreenManager ScreenManager; -TelnetSpy DebugPort; -CModerator BTModerator; - -sRxLine PCline; -long lastRxTime; // used to observe inter character delays -bool hasOEMController = false; - -CProtocolPackage HeaterData; - -unsigned long moderator; -bool bUpdateDisplay = false; -bool bHaveWebClient = false; -bool bBTconnected = false; - -//////////////////////////////////////////////////////////////////////////////////////////////////////// -// Bluetooth instantiation -// -#ifdef ESP32 - -// Bluetooth options for ESP32 -#if USE_HC05_BLUETOOTH == 1 -CBluetoothESP32HC05 Bluetooth(HC05_KeyPin, HC05_SensePin, Rx2Pin, Tx2Pin); // Instantiate ESP32 using a HC-05 -#elif USE_BLE_BLUETOOTH == 1 -CBluetoothESP32BLE Bluetooth; // Instantiate ESP32 BLE server -#elif USE_CLASSIC_BLUETOOTH == 1 -CBluetoothESP32Classic Bluetooth; // Instantiate ESP32 Classic Bluetooth server -#else // none selected -CBluetoothAbstract Bluetooth; // default no bluetooth support - empty shell -#endif - -#else // !ESP32 - -// Bluetooth for boards other than ESP32 -#if USE_HC05_BLUETOOTH == 1 -CBluetoothHC05 Bluetooth(HC05_KeyPin, HC05_SensePin); // Instantiate a HC-05 -#else // none selected -CBluetoothAbstract Bluetooth; // default no bluetooth support - empty shell -#endif // closing USE_HC05_BLUETOOTH - -#endif // closing ESP32 -// -// END Bluetooth instantiation -//////////////////////////////////////////////////////////////////////////////////////////////////////// - - - -//////////////////////////////////////////////////////////////////////////////////////////////////////// -// setup Non Volatile storage -// this is very much hardware dependent, we can use the ESP32's FLASH -// -#ifdef ESP32 -CESP32HeaterStorage actualNVstore; -#else -CHeaterStorage actualNVstore; // dummy, for now -#endif - - // create reference to CHeaterStorage - // via the magic of polymorphism we can use this to access whatever - // storage is required for a specific platform in a uniform way -CHeaterStorage& NVstore = actualNVstore; - -// -//////////////////////////////////////////////////////////////////////////////////////////////////////// - -CBluetoothAbstract& getBluetoothClient() -{ - return Bluetooth; -} - -// callback function for Keypad events. -// must be an absolute function, cannot be a class member due the "this" element! -void parentKeyHandler(uint8_t event) -{ - ScreenManager.keyHandler(event); // call into the Screen Manager -} - -void setup() { - - // initialise TelnetSpy (port 23) as well as Serial to 115200 - // Serial is the usual USB connection to a PC - // DO THIS BEFORE WE TRY AND SEND DEBUG INFO! - - DebugPort.setWelcomeMsg("*************************************************\r\n" - "* Connected to BTC heater controller debug port *\r\n" - "*************************************************\r\n"); - DebugPort.setBufferSize(8192); - DebugPort.begin(115200); - - - NVstore.init(); - NVstore.load(); - - KeyPad.begin(keyLeft_pin, keyRight_pin, keyCentre_pin, keyUp_pin, keyDown_pin); - KeyPad.setCallback(parentKeyHandler); - - // Initialize the rtc object - Clock.begin(); - - // initialise DS18B20 temperature sensor(s) - TempSensor.begin(); - TempSensor.setWaitForConversion(false); - TempSensor.requestTemperatures(); - lastTemperatureTime = millis(); - lastAnimationTime = millis(); - - ScreenManager.begin(); - -#if USE_WIFI == 1 - - initWifi(WiFi_TriggerPin, FAILEDSSID, FAILEDPASSWORD); -#if USE_OTA == 1 - initOTA(); -#endif // USE_OTA -#if USE_WEBSERVER == 1 - initWebServer(); -#endif // USE_WEBSERVER - -#endif // USE_WIFI - - pinMode(ListenOnlyPin, INPUT_PULLUP); // pin to enable passive mode - pinMode(LED_Pin, OUTPUT); // On board LED indicator - digitalWrite(LED_Pin, LOW); - - initBlueWireSerial(); - - // prepare for first long delay detection - lastRxTime = millis(); - - TxManage.begin(); // ensure Tx enable pin is setup - - // define defaults should OEM controller be missing - DefaultBTCParams.setTemperature_Desired(23); - DefaultBTCParams.setTemperature_Actual(22); - DefaultBTCParams.Controller.OperatingVoltage = 120; - DefaultBTCParams.setPump_Min(1.6f); - DefaultBTCParams.setPump_Max(5.5f); - DefaultBTCParams.setFan_Min(1680); - DefaultBTCParams.setFan_Max(4500); - - bBTconnected = false; - Bluetooth.begin(); - -} - - - -// main functional loop is based about a state machine approach, waiting for data -// to appear upon the blue wire, and marshalling into an appropriate receive buffers -// according to the state. - -void loop() -{ - - float fTemperature; - unsigned long timenow = millis(); - - DebugPort.handle(); // keep telnet spy alive - -#if USE_WIFI == 1 - - doWiFiManager(); -#if USE_OTA == 1 - DoOTA(); -#endif // USE_OTA -#if USE_WEBSERVER == 1 - bHaveWebClient = doWebServer(); -#endif //USE_WEBSERVER - -#endif // USE_WIFI - - checkDebugCommands(); - - KeyPad.update(); // scan keypad - key presses handler via callback functions! - - Bluetooth.check(); // check for Bluetooth activity - - if(Bluetooth.isConnected()) { - if(!bBTconnected) { - bBTconnected = true; - BTModerator.reset(); - } - } - else { - bBTconnected = false; - } - - - ////////////////////////////////////////////////////////////////////////////////////// - // Blue wire data reception - // Reads data from the "blue wire" Serial port, (to/from heater) - // If an OEM controller exists we will also see it's data frames - // Note that the data is read now, then held for later use in the state machine - // - sRxData BlueWireData; - - if (BlueWireSerial.available()) { - // Data is avaialable, read and store it now, use it later - // Note that if not in a recognised data receive frame state, the data - // will be deliberately lost! - BlueWireData.setValue(BlueWireSerial.read()); // read hex byte, store for later use - - lastRxTime = timenow; // tickle last rx time, for rx data timeout purposes - } - - - // calc elapsed time since last rxd byte - // used to detect no OEM controller, or the start of an OEM frame sequence - unsigned long RxTimeElapsed = timenow - lastRxTime; - - // precautionary state machine action if all 24 bytes were not received - // whilst expecting a frame from the blue wire - if(RxTimeElapsed > RX_DATA_TIMOUT) { - if( CommState.is(CommStates::OEMCtrlRx) || - CommState.is(CommStates::HeaterRx1) || - CommState.is(CommStates::HeaterRx2) ) { - - if(RxTimeElapsed >= moderator) { - moderator += 10; - DebugPort.print(RxTimeElapsed); - DebugPort.print("ms - "); - if(CommState.is(CommStates::OEMCtrlRx)) { - DebugPort.println("Timeout collecting OEM controller data, returning to Idle State"); - } - else if(CommState.is(CommStates::HeaterRx1)) { - DebugPort.println("Timeout collecting OEM heater response data, returning to Idle State"); - } - else { - DebugPort.println("Timeout collecting BTC heater response data, returning to Idle State"); - } - } - - DebugPort.println("Recycling blue wire serial interface"); - initBlueWireSerial(); -// CommState.set(CommStates::Idle); // revert to idle mode, after passing thru temperature mode - CommState.set(CommStates::TemperatureRead); // revert to idle mode, after passing thru temperature mode - } - } - - /////////////////////////////////////////////////////////////////////////////////////////// - // do our state machine to track the reception and delivery of blue wire data - - long tDelta; - switch(CommState.get()) { - - case CommStates::Idle: - - moderator = 50; - -#if RX_LED == 1 - digitalWrite(LED_Pin, LOW); -#endif - // Detect the possible start of a new frame sequence from an OEM controller - // This will be the first activity for considerable period on the blue wire - // The heater always responds to a controller frame, but otherwise never by itself - if(RxTimeElapsed >= 970) { - // have not seen any receive data for a second. - // OEM controller is probably not connected. - // Skip state machine immediately to BTC_Tx, sending our own settings. - hasOEMController = false; - bool isBTCmaster = true; - TxManage.PrepareFrame(DefaultBTCParams, isBTCmaster); // use our parameters, and mix in NV storage values - TxManage.Start(timenow); - CommState.set(CommStates::BTC_Tx); - break; - } - -#if SUPPORT_OEM_CONTROLLER == 1 - if(BlueWireData.available() && (RxTimeElapsed > RX_DATA_TIMOUT+10)) { -#ifdef REPORT_OEM_RESYNC - DebugPort.print("Re-sync'd with OEM Controller. "); - DebugPort.print(RxTimeElapsed); - DebugPort.println("ms Idle time."); -#endif - hasOEMController = true; - CommState.set(CommStates::OEMCtrlRx); // we must add this new byte! - // - // ** IMPORTANT - we must drop through to OEMCtrlRx *NOW* (skipping break) ** - // - } - else { - Clock.update(); - checkDisplayUpdate(); - break; // only break if we fail all Idle state tests - } -#else - Clock.update(); - checkDisplayUpdate(); - break; -#endif - - - case CommStates::OEMCtrlRx: - -#if RX_LED == 1 - digitalWrite(LED_Pin, HIGH); -#endif - // collect OEM controller frame - if(BlueWireData.available()) { - if(CommState.collectData(OEMCtrlFrame, BlueWireData.getValue()) ) { - CommState.set(CommStates::OEMCtrlReport); // collected 24 bytes, move on! - } - } - break; - - - case CommStates::OEMCtrlReport: -#if RX_LED == 1 - digitalWrite(LED_Pin, LOW); -#endif - // test for valid CRC, abort and restarts Serial1 if invalid - if(!validateFrame(OEMCtrlFrame, "OEM")) { - break; - } - - // filled OEM controller frame, report - // echo received OEM controller frame over Bluetooth, using [OEM] header - // note that Rotary Knob and LED OEM controllers can flood the Bluetooth - // handling at the client side, moderate OEM Bluetooth delivery - if(OEMCtrlFrame.elapsedTime() > OEM_TO_BLUETOOTH_MODERATION_TIME) { -// Bluetooth.sendFrame("[OEM]", OEMCtrlFrame, TERMINATE_OEM_LINE); - OEMCtrlFrame.setTime(); - } - else { -#if REPORT_SUPPRESSED_OEM_DATA_FRAMES != 0 - DebugPort.println("Suppressed delivery of OEM frame"); -#endif - } - CommState.set(CommStates::HeaterRx1); - break; - - - case CommStates::HeaterRx1: -#if RX_LED == 1 - digitalWrite(LED_Pin, HIGH); -#endif - // collect heater frame, always in response to an OEM controller frame - if(BlueWireData.available()) { - if( CommState.collectData(HeaterFrame1, BlueWireData.getValue()) ) { - CommState.set(CommStates::HeaterReport1); - } - } - break; - - - case CommStates::HeaterReport1: -#if RX_LED == 1 - digitalWrite(LED_Pin, LOW); -#endif - - // test for valid CRC, abort and restarts Serial1 if invalid - if(!validateFrame(HeaterFrame1, "RX1")) { - break; - } - - // received heater frame (after controller message), report - - // do some monitoring of the heater state variable - // if abnormal transitions, introduce a smart error! - // This will also cancel ON/OFF requests if runstate in startup/shutdown - SmartError.monitor(HeaterFrame1); - - // echo heater reponse data to Bluetooth client - // note that Rotary Knob and LED OEM controllers can flood the Bluetooth - // handling at the client side, moderate OEM Bluetooth delivery - if(HeaterFrame1.elapsedTime() > OEM_TO_BLUETOOTH_MODERATION_TIME) { -// Bluetooth.sendFrame("[HTR]", HeaterFrame1, true); - HeaterFrame1.setTime(); - } - else { -#if REPORT_SUPPRESSED_OEM_DATA_FRAMES != 0 - DebugPort.println("Suppressed delivery of OEM heater response frame"); -#endif - } - - if(digitalRead(ListenOnlyPin)) { - bool isBTCmaster = false; - while(BlueWireSerial.available()) { - DebugPort.println("DUMPED ROGUE RX DATA"); - BlueWireSerial.read(); - } - BlueWireSerial.flush(); - TxManage.PrepareFrame(OEMCtrlFrame, isBTCmaster); // parrot OEM parameters, but block NV modes - TxManage.Start(timenow); - CommState.set(CommStates::BTC_Tx); - } - else { -// CommState.set(CommStates::Idle); // "Listen Only" input is held low, don't send out Tx - HeaterData.set(HeaterFrame1, OEMCtrlFrame); -// pRxFrame = &HeaterFrame1; -// pTxFrame = &OEMCtrlFrame; - CommState.set(CommStates::TemperatureRead); // "Listen Only" input is held low, don't send out Tx - } - break; - - - case CommStates::BTC_Tx: - // Handle time interval where we send data to the blue wire - lastRxTime = timenow; // *we* are pumping onto blue wire, track this activity! - if(TxManage.CheckTx(timenow) ) { // monitor progress of our data delivery - if(!hasOEMController) { - // only convey this frames to Bluetooth when NOT using an OEM controller! -// Bluetooth.sendFrame("[BTC]", TxManage.getFrame(), TERMINATE_BTC_LINE); // BTC => Bluetooth Controller :-) -// Bluetooth.send( createJSON("RunState", 1.50 ) ); - } - CommState.set(CommStates::HeaterRx2); // then await heater repsonse - } - break; - - - case CommStates::HeaterRx2: -#if RX_LED == 1 - digitalWrite(LED_Pin, HIGH); -#endif - // collect heater frame, in response to our control frame - if(BlueWireData.available()) { -#ifdef BADSTARTCHECK - if(!CommState.checkValidStart(BlueWireData.getValue())) { - DebugPort.println("***** Invalid start of frame - restarting Serial port *****"); - initBlueWireSerial(); - CommState.set(CommStates::Idle); - } - else { - if( CommState.collectData(HeaterFrame2, BlueWireData.getValue()) ) { - CommState.set(CommStates::HeaterReport2); - } - } -#else - if( CommState.collectData(HeaterFrame2, BlueWireData.getValue()) ) { - CommState.set(CommStates::HeaterReport2); - } -#endif - } - break; - - - case CommStates::HeaterReport2: -#if RX_LED == 1 - digitalWrite(LED_Pin, LOW); -#endif - - // test for valid CRC, abort and restarts Serial1 if invalid - if(!validateFrame(HeaterFrame2, "RX2")) { - break; - } - - // received heater frame (after our control message), report - - // do some monitoring of the heater state variables - // if abnormal transitions, introduce a smart error! - SmartError.monitor(HeaterFrame2); - - delay(5); - if(!hasOEMController) { - // only convey these frames to Bluetooth when NOT using an OEM controller! -// Bluetooth.sendFrame("[HTR]", HeaterFrame2, true); // pin not grounded, suppress duplicate to BT - } - CommState.set(CommStates::TemperatureRead); - HeaterData.set(HeaterFrame2, TxManage.getFrame()); -// pRxFrame = &HeaterFrame2; -// pTxFrame = &TxManage.getFrame(); - break; - - case CommStates::TemperatureRead: - // update temperature reading, - // synchronised with serial reception as interrupts do get disabled in the OneWire library - tDelta = timenow - lastTemperatureTime; - if(tDelta > TEMPERATURE_INTERVAL) { // maintain a minimum holdoff period - lastTemperatureTime += TEMPERATURE_INTERVAL; // reset time to observe temeprature - fTemperature = TempSensor.getTempCByIndex(0); // read sensor - // initialise filtered temperature upon very first pass - if(fFilteredTemperature <= -90) { // avoid FP exactness issues - fFilteredTemperature = fTemperature; // prime with initial reading - } - // exponential mean to stabilse readings - fFilteredTemperature = fFilteredTemperature * fAlpha + (1-fAlpha) * fTemperature; - DefaultBTCParams.setTemperature_Actual((unsigned char)(fFilteredTemperature + 0.5)); // update [BTC] frame to send - TempSensor.requestTemperatures(); // prep sensor for future reading - ScreenManager.reqUpdate(); - } - CommState.set(CommStates::Idle); - updateJsonBT(); - break; - } // switch(CommState) - - BlueWireData.reset(); // ensure we flush any used data - -} // loop - -void DebugReportFrame(const char* hdr, const CProtocol& Frame, const char* ftr) -{ - DebugPort.print(hdr); // header - for(int i=0; i<24; i++) { - char str[16]; - sprintf(str, " %02X", Frame.Data[i]); // build 2 dig hex values - DebugPort.print(str); // and print - } - DebugPort.print(ftr); // footer -} - - - -void initBlueWireSerial() -{ - // initialize serial port to interact with the "blue wire" - // 25000 baud, Tx and Rx channels of Chinese heater comms interface: - // Tx/Rx data to/from heater, - // Note special baud rate for Chinese heater controllers -#if defined(__arm__) || defined(__AVR__) - BlueWireSerial.begin(25000); - pinMode(Rx1Pin, INPUT_PULLUP); // required for MUX to work properly -#elif ESP32 - // ESP32 - BlueWireSerial.begin(25000, SERIAL_8N1, Rx1Pin, Tx1Pin); // need to explicitly specify pins for pin multiplexer! - pinMode(Rx1Pin, INPUT_PULLUP); // required for MUX to work properly -#endif -} - -bool validateFrame(const CProtocol& frame, const char* name) -{ - if(!frame.verifyCRC()) { - // Bad CRC - restart blue wire Serial port - DebugPort.print("\007Bad CRC detected for "); - DebugPort.print(name); - DebugPort.println(" frame - restarting blue wire's serial port"); - char header[16]; - sprintf(header, "[CRC_%s]", name); - DebugReportFrame(header, frame, "\r\n"); - initBlueWireSerial(); - CommState.set(CommStates::Idle); - return false; - } - return true; -} - - -void requestOn() -{ - TxManage.queueOnRequest(); - SmartError.reset(); - Bluetooth.setRefTime(); -} - -void requestOff() -{ - TxManage.queueOffRequest(); - SmartError.inhibit(); - Bluetooth.setRefTime(); -} - -void ToggleOnOff() -{ - if(HeaterData.getRunState()) { - DebugPort.println("ToggleOnOff: Heater OFF"); - requestOff(); - } - else { - DebugPort.println("ToggleOnOff: Heater ON"); - requestOn(); - } -} - - -void reqTemp(unsigned char newTemp) -{ - unsigned char max = DefaultBTCParams.getTemperature_Max(); - unsigned char min = DefaultBTCParams.getTemperature_Min(); - if(newTemp >= max) - newTemp = max; - if(newTemp <= min) - newTemp = min; - - NVstore.setDesiredTemperature(newTemp); - - ScreenManager.reqUpdate(); -} - -void reqTempDelta(int delta) -{ - unsigned char newTemp = getSetTemp() + delta; - - reqTemp(newTemp); -} - -int getSetTemp() -{ - return NVstore.getDesiredTemperature(); -} - -void reqThermoToggle() -{ - setThermostatMode(getThermostatMode() ? 0 : 1); -} - -void setThermostatMode(unsigned char val) -{ - NVstore.setThermostatMode(val); -} - - -bool getThermostatMode() -{ - return NVstore.getThermostatMode() != 0; -} - -void checkDisplayUpdate() -{ - // only update OLED when not processing blue wire - if(ScreenManager.checkUpdate()) { - lastAnimationTime = millis() + 100; - ScreenManager.animate(); - ScreenManager.refresh(); // always refresh post major update - } - - - long tDelta = millis() - lastAnimationTime; - if(tDelta >= 100) { - lastAnimationTime = millis() + 100; - if(ScreenManager.animate()) - ScreenManager.refresh(); - } -} - -void reqPumpPrime(bool on) -{ - DefaultBTCParams.setPump_Prime(on); -} - -float getActualTemperature() -{ - return fFilteredTemperature; -} - -void setPumpMin(float val) -{ - NVstore.setPmin(val); -} - -void setPumpMax(float val) -{ - NVstore.setPmax(val); -} - -void setFanMin(short cVal) -{ - NVstore.setFmin(cVal); -} - -void setFanMax(short cVal) -{ - NVstore.setFmax(cVal); -} - -void saveNV() -{ - NVstore.save(); -} - -const CProtocolPackage& getHeaterInfo() -{ - return HeaterData; -} - -bool isWebClientConnected() -{ - return bHaveWebClient; -} - -void checkDebugCommands() -{ - // check for test commands received from PC Over USB - if(DebugPort.available()) { - static int mode = 0; - static int val = 0; - - char rxVal = DebugPort.read(); - - bool bSendVal = false; - if(isControl(rxVal)) { // "End of Line" - String convert(PCline.Line); - val = convert.toInt(); - bSendVal = true; - PCline.clear(); - } - else { - if(isDigit(rxVal)) { - PCline.append(rxVal); - } - else if((rxVal == 'p') || (rxVal == 'P')) { - DebugPort.println("Test Priming Byte... "); - mode = 1; - } - else if((rxVal == 'g') || (rxVal == 'G')) { - DebugPort.println("Test glow power byte... "); - mode = 2; - } - else if((rxVal == 'i') || (rxVal == 'I')) { - DebugPort.println("Test fan bytes"); - mode = 3; - } - else if(rxVal == '+') { - TxManage.queueOnRequest(); - Bluetooth.setRefTime(); // reset time reference "run time" - } - else if(rxVal == '-') { - TxManage.queueOffRequest(); - Bluetooth.setRefTime(); - } - else if(rxVal == ']') { - val++; - bSendVal = true; - } - else if(rxVal == 'r') { - ESP.restart(); // reset the esp - } - else if(rxVal == '[') { - val--; - bSendVal = true; - } - } - if(bSendVal) { - switch(mode) { - case 1: - DefaultBTCParams.Controller.Prime = val & 0xff; // always 0x32:Thermostat, 0xCD:Fixed - break; - case 2: - DefaultBTCParams.Controller.MinTempRise = val & 0xff; // always 0x05 - break; - case 3: - DefaultBTCParams.Controller.Unknown2_MSB = (val >> 8) & 0xff; // always 0x0d - DefaultBTCParams.Controller.Unknown2_LSB = (val >> 0) & 0xff; // always 0xac 16bit: "3500" ?? Ignition fan max RPM???? - break; - } - } - } -} - -void updateJsonBT() -{ - char jsonStr[512]; - - if(makeJsonString(BTModerator, jsonStr, 512)) { - Bluetooth.send( jsonStr ); - } -} - - -void resetBTModerator() -{ - BTModerator.reset(); -} diff --git a/Arduino/BTCDieselHeater/CppProperties.json b/Arduino/BTCDieselHeater/CppProperties.json deleted file mode 100644 index 2884111..0000000 --- a/Arduino/BTCDieselHeater/CppProperties.json +++ /dev/null @@ -1,83 +0,0 @@ -{ - "configurations": [ - { - "name": "Visual Micro", - "intelliSenseMode": "msvc-x64", - "includePath": [ - "${projectRoot}..\\SenderTrial2", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries\\Preferences\\src", - "${projectRoot}..\\..\\..\\libraries\\WifiManager", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries\\WiFi\\src", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries\\WebServer\\src", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries\\DNSServer\\src", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries\\ArduinoOTA\\src", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries\\Update\\src", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries\\FS\\src", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries\\ESPmDNS\\src", - "${projectRoot}..\\..\\..\\libraries\\telnetspy-master", - "${projectRoot}..\\..\\..\\..\\..\\..\\..\\Program Files (x86)\\Arduino\\libraries", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\libraries", - "${projectRoot}..\\..\\..\\libraries", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\cores\\esp32", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\cores\\esp32\\libb64", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\variants\\doitESP32devkitV1", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\config", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\bluedroid", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\bluedroid\\api", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\app_trace", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\app_update", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\bootloader_support", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\bt", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\driver", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\esp32", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\esp_adc_cal", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\esp_http_client", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\esp-tls", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\ethernet", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\fatfs", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\freertos", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\heap", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\jsmn", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\log", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\mdns", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\mbedtls", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\mbedtls_port", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\newlib", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\nvs_flash", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\openssl", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\spi_flash", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\sdmmc", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\smartconfig_ack", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\spiffs", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\tcpip_adapter", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\ulp", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\vfs", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\wear_levelling", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\xtensa-debug-module", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\coap", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\console", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\expat", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\json", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\lwip", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\nghttp", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\soc", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include\\wpa_supplicant", - "${projectRoot}..\\..\\..\\..\\..\\AppData\\Local\\arduino15\\packages\\esp32\\hardware\\esp32\\1.0.0\\tools\\sdk\\include" - ], - "defines": [ - "__ESP32_ESp32__", - "__ESP32_ESP32__", - "ESP_PLATFORM", - "HAVE_CONFIG_H", - "F_CPU=240000000L", - "ARDUINO=10805", - "ARDUINO_ESP32_DEV", - "ARDUINO_ARCH_ESP32", - "ESP32", - "CORE_DEBUG_LEVEL=0", - "__cplusplus=201103L", - "_VMICRO_INTELLISENSE" - ] - } - ] -} \ No newline at end of file diff --git a/Arduino/BTCDieselHeater/BluetoothAbstract.h b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothAbstract.h similarity index 94% rename from Arduino/BTCDieselHeater/BluetoothAbstract.h rename to Arduino/BTCDieselHeater/src/Bluetooth/BluetoothAbstract.h index e58f1b3..6131b95 100644 --- a/Arduino/BTCDieselHeater/BluetoothAbstract.h +++ b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothAbstract.h @@ -23,9 +23,9 @@ #define __BLUETOOTHABSTRACT_H__ #include -#include "UtilClasses.h" -#include "Debugport.h" -#include "helpers.h" +#include "../Utility/UtilClasses.h" +#include "../Utility/Debugport.h" +#include "../Protocol/helpers.h" class CProtocol; diff --git a/Arduino/BTCDieselHeater/BluetoothESP32.cpp b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothESP32.cpp similarity index 98% rename from Arduino/BTCDieselHeater/BluetoothESP32.cpp rename to Arduino/BTCDieselHeater/src/Bluetooth/BluetoothESP32.cpp index 2702ba6..24d28e8 100644 --- a/Arduino/BTCDieselHeater/BluetoothESP32.cpp +++ b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothESP32.cpp @@ -20,11 +20,11 @@ */ #include -#include "pins.h" -#include "Protocol.h" -#include "debugport.h" +#include "../cfg/pins.h" +#include "../Protocol/Protocol.h" +#include "../Utility/debugport.h" #include "BluetoothESP32.h" -#include "BTCConfig.h" +#include "../cfg/BTCConfig.h" diff --git a/Arduino/BTCDieselHeater/BluetoothESP32.h b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothESP32.h similarity index 100% rename from Arduino/BTCDieselHeater/BluetoothESP32.h rename to Arduino/BTCDieselHeater/src/Bluetooth/BluetoothESP32.h diff --git a/Arduino/BTCDieselHeater/BluetoothHC05.cpp b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothHC05.cpp similarity index 97% rename from Arduino/BTCDieselHeater/BluetoothHC05.cpp rename to Arduino/BTCDieselHeater/src/Bluetooth/BluetoothHC05.cpp index 6cb7f5e..168b282 100644 --- a/Arduino/BTCDieselHeater/BluetoothHC05.cpp +++ b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothHC05.cpp @@ -19,12 +19,12 @@ * */ -#include "pins.h" -#include "Protocol.h" -#include "debugport.h" #include "BluetoothHC05.h" -#include "BTCConfig.h" -#include "helpers.h" +#include "../cfg/pins.h" +#include "../cfg/BTCConfig.h" +#include "../Protocol/Protocol.h" +#include "../Protocol/helpers.h" +#include "../Utility/DebugPort.h" // Bluetooth access via HC-05 Module, using a UART diff --git a/Arduino/BTCDieselHeater/BluetoothHC05.h b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothHC05.h similarity index 98% rename from Arduino/BTCDieselHeater/BluetoothHC05.h rename to Arduino/BTCDieselHeater/src/Bluetooth/BluetoothHC05.h index 9900cb1..3c60654 100644 --- a/Arduino/BTCDieselHeater/BluetoothHC05.h +++ b/Arduino/BTCDieselHeater/src/Bluetooth/BluetoothHC05.h @@ -21,7 +21,7 @@ #include "BluetoothAbstract.h" -#include "Moderator.h" +#include "../Utility/Moderator.h" // Define the serial port for access to a HC-05 module. // This is generally Serial2, but different platforms use diff --git a/Arduino/BTCDieselHeater/128x64OLED.cpp b/Arduino/BTCDieselHeater/src/OLED/128x64OLED.cpp similarity index 99% rename from Arduino/BTCDieselHeater/128x64OLED.cpp rename to Arduino/BTCDieselHeater/src/OLED/128x64OLED.cpp index a151989..6d27926 100644 --- a/Arduino/BTCDieselHeater/128x64OLED.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/128x64OLED.cpp @@ -21,7 +21,7 @@ #include "128x64OLED.h" -#include "DebugPort.h" +#include "../Utility/DebugPort.h" #define DBG DebugPort.print #define DBGln DebugPort.println diff --git a/Arduino/BTCDieselHeater/128x64OLED.h b/Arduino/BTCDieselHeater/src/OLED/128x64OLED.h similarity index 94% rename from Arduino/BTCDieselHeater/128x64OLED.h rename to Arduino/BTCDieselHeater/src/OLED/128x64OLED.h index e76db45..5a291c3 100644 --- a/Arduino/BTCDieselHeater/128x64OLED.h +++ b/Arduino/BTCDieselHeater/src/OLED/128x64OLED.h @@ -22,10 +22,10 @@ #ifndef __128x64OLED_H__ #define __128x64OLED_H__ -#include "Adafruit_SH1106.h" +#include -#include "FontTypes.h" -#include "UtilClasses.h" +#include "fonts/FontTypes.h" +#include "../Utility/UtilClasses.h" class C128x64_OLED : public Adafruit_SH1106 { const FONT_INFO* m_pFontInfo; diff --git a/Arduino/BTCDieselHeater/Screen.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen.cpp similarity index 100% rename from Arduino/BTCDieselHeater/Screen.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen.cpp diff --git a/Arduino/BTCDieselHeater/Screen.h b/Arduino/BTCDieselHeater/src/OLED/Screen.h similarity index 96% rename from Arduino/BTCDieselHeater/Screen.h rename to Arduino/BTCDieselHeater/src/OLED/Screen.h index acf8e50..109e2f3 100644 --- a/Arduino/BTCDieselHeater/Screen.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen.h @@ -23,10 +23,10 @@ #define __SCREEN_H__ #include -#include "FontTypes.h" -#include "UtilClasses.h" -#include "ScreenManager.h" #include "128x64OLED.h" +#include "ScreenManager.h" +#include "fonts/FontTypes.h" +#include "../Utility/UtilClasses.h" class CProtocol; diff --git a/Arduino/BTCDieselHeater/Screen1.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen1.cpp similarity index 98% rename from Arduino/BTCDieselHeater/Screen1.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen1.cpp index 40b1876..df1efa5 100644 --- a/Arduino/BTCDieselHeater/Screen1.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/Screen1.cpp @@ -20,14 +20,14 @@ */ #include "128x64OLED.h" -#include "MiniFont.h" -#include "Icons.h" -#include "BluetoothAbstract.h" +#include "fonts/MiniFont.h" +#include "fonts/Icons.h" +#include "../Bluetooth/BluetoothAbstract.h" #include "Screen1.h" -#include "BTCWifi.h" +#include "../Wifi/BTCWifi.h" #include "KeyPad.h" -#include "helpers.h" -#include "Protocol.h" +#include "../Protocol/helpers.h" +#include "../Protocol/Protocol.h" #define MINIFONT miniFontInfo diff --git a/Arduino/BTCDieselHeater/Screen1.h b/Arduino/BTCDieselHeater/src/OLED/Screen1.h similarity index 98% rename from Arduino/BTCDieselHeater/Screen1.h rename to Arduino/BTCDieselHeater/src/OLED/Screen1.h index e51a71d..b89e210 100644 --- a/Arduino/BTCDieselHeater/Screen1.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen1.h @@ -19,7 +19,7 @@ * */ -#include "stdint.h" +#include #include "ScreenHeader.h" class C128x64_OLED; diff --git a/Arduino/BTCDieselHeater/Screen2.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen2.cpp similarity index 98% rename from Arduino/BTCDieselHeater/Screen2.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen2.cpp index f197171..6b01c09 100644 --- a/Arduino/BTCDieselHeater/Screen2.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/Screen2.cpp @@ -20,12 +20,12 @@ */ #include "128x64OLED.h" -#include "tahoma16.h" -#include "Icons.h" +#include "fonts/tahoma16.h" +#include "fonts/Icons.h" #include "Screen2.h" #include "KeyPad.h" -#include "helpers.h" -#include "UtilClasses.h" +#include "../Protocol/helpers.h" +#include "../Utility/UtilClasses.h" #define MAXIFONT tahoma_16ptFontInfo diff --git a/Arduino/BTCDieselHeater/Screen2.h b/Arduino/BTCDieselHeater/src/OLED/Screen2.h similarity index 98% rename from Arduino/BTCDieselHeater/Screen2.h rename to Arduino/BTCDieselHeater/src/OLED/Screen2.h index 757ee15..be5a1ca 100644 --- a/Arduino/BTCDieselHeater/Screen2.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen2.h @@ -19,7 +19,7 @@ * */ -#include "stdint.h" +#include #include "ScreenHeader.h" class C128x64_OLED; diff --git a/Arduino/BTCDieselHeater/Screen3.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen3.cpp similarity index 99% rename from Arduino/BTCDieselHeater/Screen3.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen3.cpp index 22a6410..43f379a 100644 --- a/Arduino/BTCDieselHeater/Screen3.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/Screen3.cpp @@ -19,10 +19,9 @@ * */ -#include "128x64OLED.h" -#include "KeyPad.h" -#include "helpers.h" #include "Screen3.h" +#include "KeyPad.h" +#include "../Protocol/helpers.h" /////////////////////////////////////////////////////////////////////////// // diff --git a/Arduino/BTCDieselHeater/Screen3.h b/Arduino/BTCDieselHeater/src/OLED/Screen3.h similarity index 98% rename from Arduino/BTCDieselHeater/Screen3.h rename to Arduino/BTCDieselHeater/src/OLED/Screen3.h index ea76bd6..ac409bb 100644 --- a/Arduino/BTCDieselHeater/Screen3.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen3.h @@ -19,7 +19,7 @@ * */ -#include "stdint.h" +#include #include "ScreenHeader.h" class C128x64_OLED; diff --git a/Arduino/BTCDieselHeater/Screen4.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen4.cpp similarity index 93% rename from Arduino/BTCDieselHeater/Screen4.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen4.cpp index 45f77bf..a97274f 100644 --- a/Arduino/BTCDieselHeater/Screen4.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/Screen4.cpp @@ -19,14 +19,13 @@ * */ -#include "128x64OLED.h" -#include "KeyPad.h" -#include "helpers.h" #include "Screen4.h" -#include "BTCWifi.h" -#include "Tahoma8.h" -#include "FranklinGothic.h" -#include "src/fonts/Arial.h" +#include "KeyPad.h" +#include "../Protocol/helpers.h" +#include "../Wifi/BTCWifi.h" +#include "fonts/Tahoma8.h" +#include "fonts/FranklinGothic.h" +#include "fonts/Arial.h" /////////////////////////////////////////////////////////////////////////// // diff --git a/Arduino/BTCDieselHeater/Screen4.h b/Arduino/BTCDieselHeater/src/OLED/Screen4.h similarity index 98% rename from Arduino/BTCDieselHeater/Screen4.h rename to Arduino/BTCDieselHeater/src/OLED/Screen4.h index 57b6b6d..8577bd7 100644 --- a/Arduino/BTCDieselHeater/Screen4.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen4.h @@ -19,7 +19,7 @@ * */ -#include "stdint.h" +#include #include "ScreenHeader.h" class C128x64_OLED; diff --git a/Arduino/BTCDieselHeater/Screen5.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen5.cpp similarity index 98% rename from Arduino/BTCDieselHeater/Screen5.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen5.cpp index 454d55a..9cdb124 100644 --- a/Arduino/BTCDieselHeater/Screen5.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/Screen5.cpp @@ -28,12 +28,11 @@ // /////////////////////////////////////////////////////////////////////////// -#include "128x64OLED.h" -#include "KeyPad.h" -#include "helpers.h" #include "Screen5.h" -#include "BTCWifi.h" -#include "src/fonts/Arial.h" +#include "KeyPad.h" +#include "../Protocol/helpers.h" +#include "../Wifi/BTCWifi.h" +#include "fonts/Arial.h" CScreen5::CScreen5(C128x64_OLED& display, CScreenManager& mgr) : CScreenHeader(display, mgr) diff --git a/Arduino/BTCDieselHeater/Screen5.h b/Arduino/BTCDieselHeater/src/OLED/Screen5.h similarity index 98% rename from Arduino/BTCDieselHeater/Screen5.h rename to Arduino/BTCDieselHeater/src/OLED/Screen5.h index eb3649d..c6b173e 100644 --- a/Arduino/BTCDieselHeater/Screen5.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen5.h @@ -19,7 +19,7 @@ * */ -#include "stdint.h" +#include #include "ScreenHeader.h" class C128x64_OLED; diff --git a/Arduino/BTCDieselHeater/Screen6.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen6.cpp similarity index 98% rename from Arduino/BTCDieselHeater/Screen6.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen6.cpp index e835c8d..cd621fa 100644 --- a/Arduino/BTCDieselHeater/Screen6.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/Screen6.cpp @@ -28,12 +28,11 @@ // /////////////////////////////////////////////////////////////////////////// -#include "128x64OLED.h" -#include "KeyPad.h" -#include "helpers.h" #include "Screen6.h" -#include "src/fonts/Arial.h" -#include "Clock.h" +#include "KeyPad.h" +#include "../Protocol/helpers.h" +#include "fonts/Arial.h" +#include "../RTC/Clock.h" CScreen6::CScreen6(C128x64_OLED& display, CScreenManager& mgr) : CScreenHeader(display, mgr) diff --git a/Arduino/BTCDieselHeater/Screen6.h b/Arduino/BTCDieselHeater/src/OLED/Screen6.h similarity index 95% rename from Arduino/BTCDieselHeater/Screen6.h rename to Arduino/BTCDieselHeater/src/OLED/Screen6.h index 1d85e96..0448b7e 100644 --- a/Arduino/BTCDieselHeater/Screen6.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen6.h @@ -19,9 +19,9 @@ * */ -#include "stdint.h" +#include #include "ScreenHeader.h" -#include "BTCDateTime.h" +#include "../RTC/BTCDateTime.h" class C128x64_OLED; class CScreenManager; diff --git a/Arduino/BTCDieselHeater/Screen7.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen7.cpp similarity index 98% rename from Arduino/BTCDieselHeater/Screen7.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen7.cpp index bf64279..4264be2 100644 --- a/Arduino/BTCDieselHeater/Screen7.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/Screen7.cpp @@ -28,12 +28,11 @@ // /////////////////////////////////////////////////////////////////////////// -#include "128x64OLED.h" -#include "KeyPad.h" -#include "helpers.h" #include "Screen7.h" -#include "NVStorage.h" -#include "RTClib.h" +#include "KeyPad.h" +#include "../Protocol/helpers.h" +#include "../Utility/NVStorage.h" +#include const char* briefDOW[] = { "S", "M", "T", "W", "T", "F", "S" }; diff --git a/Arduino/BTCDieselHeater/Screen7.h b/Arduino/BTCDieselHeater/src/OLED/Screen7.h similarity index 95% rename from Arduino/BTCDieselHeater/Screen7.h rename to Arduino/BTCDieselHeater/src/OLED/Screen7.h index d07f2bb..1f1ce0e 100644 --- a/Arduino/BTCDieselHeater/Screen7.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen7.h @@ -19,9 +19,9 @@ * */ -#include "stdint.h" +#include #include "ScreenHeader.h" -#include "NVStorage.h" +#include "../Utility/NVStorage.h" class C128x64_OLED; class CScreenManager; diff --git a/Arduino/BTCDieselHeater/Screen8.cpp b/Arduino/BTCDieselHeater/src/OLED/Screen8.cpp similarity index 96% rename from Arduino/BTCDieselHeater/Screen8.cpp rename to Arduino/BTCDieselHeater/src/OLED/Screen8.cpp index 9edfe7b..3634851 100644 --- a/Arduino/BTCDieselHeater/Screen8.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/Screen8.cpp @@ -19,12 +19,11 @@ * */ -#include "128x64OLED.h" -#include "KeyPad.h" -#include "helpers.h" #include "Screen8.h" -#include "Tahoma16.h" -#include "Clock.h" +#include "KeyPad.h" +#include "../Protocol/helpers.h" +#include "fonts/Tahoma16.h" +#include "../RTC/Clock.h" /////////////////////////////////////////////////////////////////////////// // diff --git a/Arduino/BTCDieselHeater/Screen8.h b/Arduino/BTCDieselHeater/src/OLED/Screen8.h similarity index 98% rename from Arduino/BTCDieselHeater/Screen8.h rename to Arduino/BTCDieselHeater/src/OLED/Screen8.h index d988bd1..6631da2 100644 --- a/Arduino/BTCDieselHeater/Screen8.h +++ b/Arduino/BTCDieselHeater/src/OLED/Screen8.h @@ -19,7 +19,7 @@ * */ -#include "stdint.h" +#include #include "ScreenHeader.h" class C128x64_OLED; diff --git a/Arduino/BTCDieselHeater/ScreenHeader.cpp b/Arduino/BTCDieselHeater/src/OLED/ScreenHeader.cpp similarity index 95% rename from Arduino/BTCDieselHeater/ScreenHeader.cpp rename to Arduino/BTCDieselHeater/src/OLED/ScreenHeader.cpp index ef42382..ba8ecdd 100644 --- a/Arduino/BTCDieselHeater/ScreenHeader.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/ScreenHeader.cpp @@ -1,15 +1,14 @@ #include #include "ScreenHeader.h" -#include "Protocol.h" -#include "128x64OLED.h" -#include "BTCWifi.h" -#include "BluetoothAbstract.h" -#include "Icons.h" -#include "MiniFont.h" -#include "helpers.h" -#include "NVStorage.h" -#include "Clock.h" -#include "src/fonts/Arial.h" +#include "../Protocol/Protocol.h" +#include "../Protocol/helpers.h" +#include "../Wifi/BTCWifi.h" +#include "../Bluetooth/BluetoothAbstract.h" +#include "../Utility/NVStorage.h" +#include "../RTC/Clock.h" +#include "fonts/Arial.h" +#include "fonts/Icons.h" +#include "fonts/MiniFont.h" #define MINIFONT miniFontInfo diff --git a/Arduino/BTCDieselHeater/ScreenHeader.h b/Arduino/BTCDieselHeater/src/OLED/ScreenHeader.h similarity index 95% rename from Arduino/BTCDieselHeater/ScreenHeader.h rename to Arduino/BTCDieselHeater/src/OLED/ScreenHeader.h index 7e10bf8..8c8acf8 100644 --- a/Arduino/BTCDieselHeater/ScreenHeader.h +++ b/Arduino/BTCDieselHeater/src/OLED/ScreenHeader.h @@ -23,9 +23,9 @@ #define __SCREEN_HEADER_H__ #include -#include "FontTypes.h" -#include "UtilClasses.h" #include "Screen.h" +#include "../Utility/UtilClasses.h" +#include "fonts/FontTypes.h" class CScreenHeader : public CScreen { diff --git a/Arduino/BTCDieselHeater/ScreenManager.cpp b/Arduino/BTCDieselHeater/src/OLED/ScreenManager.cpp similarity index 99% rename from Arduino/BTCDieselHeater/ScreenManager.cpp rename to Arduino/BTCDieselHeater/src/OLED/ScreenManager.cpp index 5c6cca7..07399bb 100644 --- a/Arduino/BTCDieselHeater/ScreenManager.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/ScreenManager.cpp @@ -1,7 +1,4 @@ #include "ScreenManager.h" -#include -#include "128x64OLED.h" -#include "pins.h" #include "Screen1.h" #include "Screen2.h" #include "Screen3.h" @@ -10,7 +7,9 @@ #include "Screen6.h" #include "Screen7.h" #include "Screen8.h" -#include "BTCConfig.h" +#include +#include "../cfg/pins.h" +#include "../cfg/BTCConfig.h" //////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/Arduino/BTCDieselHeater/ScreenManager.h b/Arduino/BTCDieselHeater/src/OLED/ScreenManager.h similarity index 100% rename from Arduino/BTCDieselHeater/ScreenManager.h rename to Arduino/BTCDieselHeater/src/OLED/ScreenManager.h diff --git a/Arduino/BTCDieselHeater/keypad.cpp b/Arduino/BTCDieselHeater/src/OLED/keypad.cpp similarity index 99% rename from Arduino/BTCDieselHeater/keypad.cpp rename to Arduino/BTCDieselHeater/src/OLED/keypad.cpp index e1b6b3d..44006e7 100644 --- a/Arduino/BTCDieselHeater/keypad.cpp +++ b/Arduino/BTCDieselHeater/src/OLED/keypad.cpp @@ -21,7 +21,7 @@ #include #include "keypad.h" -#include "pins.h" +#include "../cfg/pins.h" CKeyPad::CKeyPad() { diff --git a/Arduino/BTCDieselHeater/keypad.h b/Arduino/BTCDieselHeater/src/OLED/keypad.h similarity index 96% rename from Arduino/BTCDieselHeater/keypad.h rename to Arduino/BTCDieselHeater/src/OLED/keypad.h index bbf207b..a17130e 100644 --- a/Arduino/BTCDieselHeater/keypad.h +++ b/Arduino/BTCDieselHeater/src/OLED/keypad.h @@ -22,10 +22,8 @@ #ifndef __BTC_KEYPAD_H__ #define __BTC_KEYPAD_H__ -#include "stdint.h" +#include -//void initKeyPad(); -//uint8_t readKeys(); const uint8_t key_Left = 0x01; const uint8_t key_Right = 0x02; diff --git a/Arduino/BTCDieselHeater/Protocol.cpp b/Arduino/BTCDieselHeater/src/Protocol/Protocol.cpp similarity index 99% rename from Arduino/BTCDieselHeater/Protocol.cpp rename to Arduino/BTCDieselHeater/src/Protocol/Protocol.cpp index 4ea6bd0..bd8e06b 100644 --- a/Arduino/BTCDieselHeater/Protocol.cpp +++ b/Arduino/BTCDieselHeater/src/Protocol/Protocol.cpp @@ -21,7 +21,7 @@ #include #include "Protocol.h" -#include "debugport.h" +#include "../Utility/DebugPort.h" #include "helpers.h" diff --git a/Arduino/BTCDieselHeater/Protocol.h b/Arduino/BTCDieselHeater/src/Protocol/Protocol.h similarity index 100% rename from Arduino/BTCDieselHeater/Protocol.h rename to Arduino/BTCDieselHeater/src/Protocol/Protocol.h diff --git a/Arduino/BTCDieselHeater/SmartError.cpp b/Arduino/BTCDieselHeater/src/Protocol/SmartError.cpp similarity index 100% rename from Arduino/BTCDieselHeater/SmartError.cpp rename to Arduino/BTCDieselHeater/src/Protocol/SmartError.cpp diff --git a/Arduino/BTCDieselHeater/SmartError.h b/Arduino/BTCDieselHeater/src/Protocol/SmartError.h similarity index 100% rename from Arduino/BTCDieselHeater/SmartError.h rename to Arduino/BTCDieselHeater/src/Protocol/SmartError.h diff --git a/Arduino/BTCDieselHeater/TxManage.cpp b/Arduino/BTCDieselHeater/src/Protocol/TxManage.cpp similarity index 99% rename from Arduino/BTCDieselHeater/TxManage.cpp rename to Arduino/BTCDieselHeater/src/Protocol/TxManage.cpp index 7ddfd6d..bb7bfa4 100644 --- a/Arduino/BTCDieselHeater/TxManage.cpp +++ b/Arduino/BTCDieselHeater/src/Protocol/TxManage.cpp @@ -20,7 +20,7 @@ */ #include "TxManage.h" -#include "NVStorage.h" +#include "../Utility/NVStorage.h" extern void DebugReportFrame(const char* hdr, const CProtocol&, const char* ftr); diff --git a/Arduino/BTCDieselHeater/TxManage.h b/Arduino/BTCDieselHeater/src/Protocol/TxManage.h similarity index 100% rename from Arduino/BTCDieselHeater/TxManage.h rename to Arduino/BTCDieselHeater/src/Protocol/TxManage.h diff --git a/Arduino/BTCDieselHeater/helpers.h b/Arduino/BTCDieselHeater/src/Protocol/helpers.h similarity index 100% rename from Arduino/BTCDieselHeater/helpers.h rename to Arduino/BTCDieselHeater/src/Protocol/helpers.h diff --git a/Arduino/BTCDieselHeater/BTCDateTime.cpp b/Arduino/BTCDieselHeater/src/RTC/BTCDateTime.cpp similarity index 98% rename from Arduino/BTCDieselHeater/BTCDateTime.cpp rename to Arduino/BTCDieselHeater/src/RTC/BTCDateTime.cpp index 4fc96ef..07feee7 100644 --- a/Arduino/BTCDieselHeater/BTCDateTime.cpp +++ b/Arduino/BTCDieselHeater/src/RTC/BTCDateTime.cpp @@ -20,7 +20,7 @@ */ #include "BTCDateTime.h" -#include "helpers.h" +#include "../Protocol/helpers.h" const char* BTCDateTime::dowStr() const diff --git a/Arduino/BTCDieselHeater/BTCDateTime.h b/Arduino/BTCDieselHeater/src/RTC/BTCDateTime.h similarity index 98% rename from Arduino/BTCDieselHeater/BTCDateTime.h rename to Arduino/BTCDieselHeater/src/RTC/BTCDateTime.h index 60c0582..c26e139 100644 --- a/Arduino/BTCDieselHeater/BTCDateTime.h +++ b/Arduino/BTCDieselHeater/src/RTC/BTCDateTime.h @@ -22,7 +22,7 @@ #ifndef __BTCDATETIME_H__ #define __BTCDATETIME_H__ -#include "RTClib.h" +#include const char daysOfTheWeek[7][4] = {"Sun", "Mon", "Tue", "Wed", "Thu", "Fri", "Sat"}; diff --git a/Arduino/BTCDieselHeater/Clock.cpp b/Arduino/BTCDieselHeater/src/RTC/Clock.cpp similarity index 97% rename from Arduino/BTCDieselHeater/Clock.cpp rename to Arduino/BTCDieselHeater/src/RTC/Clock.cpp index f5d1bbd..5e70af2 100644 --- a/Arduino/BTCDieselHeater/Clock.cpp +++ b/Arduino/BTCDieselHeater/src/RTC/Clock.cpp @@ -22,11 +22,11 @@ #include #include "Clock.h" #include "BTCDateTime.h" -#include "Wire.h" -#include "RTClib.h" -#include "helpers.h" -#include "NVStorage.h" -#include "DebugPort.h" +#include +#include +#include "../Protocol/helpers.h" +#include "../Utility/NVStorage.h" +#include "../Utility/DebugPort.h" // create ONE of the RTClib supported real time clock classes diff --git a/Arduino/BTCDieselHeater/Clock.h b/Arduino/BTCDieselHeater/src/RTC/Clock.h similarity index 98% rename from Arduino/BTCDieselHeater/Clock.h rename to Arduino/BTCDieselHeater/src/RTC/Clock.h index 486b23d..faf45fb 100644 --- a/Arduino/BTCDieselHeater/Clock.h +++ b/Arduino/BTCDieselHeater/src/RTC/Clock.h @@ -23,7 +23,7 @@ #define __BTC_TIMERS_H__ #include "BTCDateTime.h" -#include "BTCConfig.h" +#include "../cfg/BTCConfig.h" class CClock { diff --git a/Arduino/BTCDieselHeater/BTC_JSON.cpp b/Arduino/BTCDieselHeater/src/Utility/BTC_JSON.cpp similarity index 99% rename from Arduino/BTCDieselHeater/BTC_JSON.cpp rename to Arduino/BTCDieselHeater/src/Utility/BTC_JSON.cpp index 3cab321..3462138 100644 --- a/Arduino/BTCDieselHeater/BTC_JSON.cpp +++ b/Arduino/BTCDieselHeater/src/Utility/BTC_JSON.cpp @@ -21,9 +21,9 @@ #include "BTC_JSON.h" #include "DebugPort.h" -#include "helpers.h" +#include "../Protocol/helpers.h" #include "NVstorage.h" -#include "BTCDateTime.h" +#include "../RTC/BTCDateTime.h" char defaultJSONstr[64]; diff --git a/Arduino/BTCDieselHeater/BTC_JSON.h b/Arduino/BTCDieselHeater/src/Utility/BTC_JSON.h similarity index 100% rename from Arduino/BTCDieselHeater/BTC_JSON.h rename to Arduino/BTCDieselHeater/src/Utility/BTC_JSON.h diff --git a/Arduino/BTCDieselHeater/Moderator.h b/Arduino/BTCDieselHeater/src/Utility/Moderator.h similarity index 100% rename from Arduino/BTCDieselHeater/Moderator.h rename to Arduino/BTCDieselHeater/src/Utility/Moderator.h diff --git a/Arduino/BTCDieselHeater/NVStorage.cpp b/Arduino/BTCDieselHeater/src/Utility/NVStorage.cpp similarity index 99% rename from Arduino/BTCDieselHeater/NVStorage.cpp rename to Arduino/BTCDieselHeater/src/Utility/NVStorage.cpp index 904db43..625b1c4 100644 --- a/Arduino/BTCDieselHeater/NVStorage.cpp +++ b/Arduino/BTCDieselHeater/src/Utility/NVStorage.cpp @@ -19,7 +19,7 @@ * */ -#include "Arduino.h" +#include #include "NVStorage.h" #include "DebugPort.h" diff --git a/Arduino/BTCDieselHeater/NVStorage.h b/Arduino/BTCDieselHeater/src/Utility/NVStorage.h similarity index 100% rename from Arduino/BTCDieselHeater/NVStorage.h rename to Arduino/BTCDieselHeater/src/Utility/NVStorage.h diff --git a/Arduino/BTCDieselHeater/UtilClasses.h b/Arduino/BTCDieselHeater/src/Utility/UtilClasses.h similarity index 98% rename from Arduino/BTCDieselHeater/UtilClasses.h rename to Arduino/BTCDieselHeater/src/Utility/UtilClasses.h index 71cf90d..08641d3 100644 --- a/Arduino/BTCDieselHeater/UtilClasses.h +++ b/Arduino/BTCDieselHeater/src/Utility/UtilClasses.h @@ -24,8 +24,8 @@ #include #include -#include "Protocol.h" -#include "debugport.h" +#include "../Protocol/Protocol.h" +#include "DebugPort.h" // a class to track the blue wire receive / transmit states diff --git a/Arduino/BTCDieselHeater/debugport.h b/Arduino/BTCDieselHeater/src/Utility/debugport.h similarity index 100% rename from Arduino/BTCDieselHeater/debugport.h rename to Arduino/BTCDieselHeater/src/Utility/debugport.h diff --git a/Arduino/BTCDieselHeater/BTCWebServer.cpp b/Arduino/BTCDieselHeater/src/WiFi/BTCWebServer.cpp similarity index 94% rename from Arduino/BTCDieselHeater/BTCWebServer.cpp rename to Arduino/BTCDieselHeater/src/WiFi/BTCWebServer.cpp index 74f55a3..1075378 100644 --- a/Arduino/BTCDieselHeater/BTCWebServer.cpp +++ b/Arduino/BTCDieselHeater/src/WiFi/BTCWebServer.cpp @@ -22,13 +22,13 @@ #include "BTCWebServer.h" -#include "DebugPort.h" -#include "TxManage.h" -#include "helpers.h" -#include "pins.h" +#include "../Utility/DebugPort.h" +#include "../Protocol/TxManage.h" +#include "../Protocol/helpers.h" +#include "../cfg/pins.h" #include "Index.h" -#include "BTC_JSON.h" -#include "Moderator.h" +#include "../Utility/BTC_JSON.h" +#include "../Utility/Moderator.h" WebServer server(80); WebSocketsServer webSocket = WebSocketsServer(81); diff --git a/Arduino/BTCDieselHeater/BTCWebServer.h b/Arduino/BTCDieselHeater/src/WiFi/BTCWebServer.h similarity index 97% rename from Arduino/BTCDieselHeater/BTCWebServer.h rename to Arduino/BTCDieselHeater/src/WiFi/BTCWebServer.h index f37ff03..bb5fb1c 100644 --- a/Arduino/BTCDieselHeater/BTCWebServer.h +++ b/Arduino/BTCDieselHeater/src/WiFi/BTCWebServer.h @@ -35,7 +35,7 @@ #include #include #include -#include "ESPAsyncWebServer.h" +#include #include diff --git a/Arduino/BTCDieselHeater/BTCWifi.cpp b/Arduino/BTCDieselHeater/src/WiFi/BTCWifi.cpp similarity index 99% rename from Arduino/BTCDieselHeater/BTCWifi.cpp rename to Arduino/BTCDieselHeater/src/WiFi/BTCWifi.cpp index 47e268d..9bbd106 100644 --- a/Arduino/BTCDieselHeater/BTCWifi.cpp +++ b/Arduino/BTCDieselHeater/src/WiFi/BTCWifi.cpp @@ -21,7 +21,7 @@ // Should be working - Jimmy C #include "BTCWifi.h" -#include "DebugPort.h" +#include "../Utility/DebugPort.h" // select which pin will trigger the configuration portal when set to LOW WiFiManager wm; diff --git a/Arduino/BTCDieselHeater/BTCWifi.h b/Arduino/BTCDieselHeater/src/WiFi/BTCWifi.h similarity index 100% rename from Arduino/BTCDieselHeater/BTCWifi.h rename to Arduino/BTCDieselHeater/src/WiFi/BTCWifi.h diff --git a/Arduino/BTCDieselHeater/BTCota.cpp b/Arduino/BTCDieselHeater/src/WiFi/BTCota.cpp similarity index 98% rename from Arduino/BTCDieselHeater/BTCota.cpp rename to Arduino/BTCDieselHeater/src/WiFi/BTCota.cpp index 6d43864..5531c4f 100644 --- a/Arduino/BTCDieselHeater/BTCota.cpp +++ b/Arduino/BTCDieselHeater/src/WiFi/BTCota.cpp @@ -20,7 +20,6 @@ */ #include "BTCota.h" -#include "debugport.h" void initOTA(){ // ArduinoOTA.setHostname("myesp32"); diff --git a/Arduino/BTCDieselHeater/BTCota.h b/Arduino/BTCDieselHeater/src/WiFi/BTCota.h similarity index 96% rename from Arduino/BTCDieselHeater/BTCota.h rename to Arduino/BTCDieselHeater/src/WiFi/BTCota.h index b7b81ca..85c2101 100644 --- a/Arduino/BTCDieselHeater/BTCota.h +++ b/Arduino/BTCDieselHeater/src/WiFi/BTCota.h @@ -22,7 +22,7 @@ #include #include #include "BTCWifi.h" -#include "DebugPort.h" +#include "../Utility/DebugPort.h" void initOTA(); void DoOTA(); diff --git a/Arduino/BTCDieselHeater/Index.h b/Arduino/BTCDieselHeater/src/WiFi/Index.h similarity index 100% rename from Arduino/BTCDieselHeater/Index.h rename to Arduino/BTCDieselHeater/src/WiFi/Index.h diff --git a/Arduino/BTCDieselHeater/mainpage.cpp b/Arduino/BTCDieselHeater/src/WiFi/mainpage.cpp similarity index 100% rename from Arduino/BTCDieselHeater/mainpage.cpp rename to Arduino/BTCDieselHeater/src/WiFi/mainpage.cpp diff --git a/Arduino/BTCDieselHeater/BTCConfig.h b/Arduino/BTCDieselHeater/src/cfg/BTCConfig.h similarity index 100% rename from Arduino/BTCDieselHeater/BTCConfig.h rename to Arduino/BTCDieselHeater/src/cfg/BTCConfig.h diff --git a/Arduino/BTCDieselHeater/pins.h b/Arduino/BTCDieselHeater/src/cfg/pins.h similarity index 100% rename from Arduino/BTCDieselHeater/pins.h rename to Arduino/BTCDieselHeater/src/cfg/pins.h diff --git a/Arduino/BTCDieselHeater/src/fonts/Arial.c b/Arduino/BTCDieselHeater/src/fonts/Arial.c deleted file mode 100644 index d06e8fa..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/Arial.c +++ /dev/null @@ -1,1466 +0,0 @@ -// -// Font data for Arial -// -// -// Generated by The Dot Factory: -// http://www.eran.io/the-dot-factory-an-lcd-font-and-image-generator/ -// -///////////////////////////////////////////////////////////////////////////////////////////////////// -// -// Dot Factory Settings -// -// Flip/Rotate Padding Removal Line Wrap Descriptors -// [X] Flip X Height(Y): None (O) At column [X] Generate descriptor array -// [ ] Flip Y Width(X): Tightest ( ) At bitmap Char Width: In Bits -// 90deg Char Height: In Bits -// Font Height: In Bits -// Comments Byte [ ] Multiple descriptor arrays -// [X] Variable Name Bit layout: RowMajor -// [X] BMP visualise [#] Order: MSBfirst Create new when exceeds [80] -// [X] Char descriptor Format: Hex -// Style: Cpp Leading: 0x Image width: In Bits -// Image height: In Bits -// Variable name format -// Bitmaps: const uint8_t PROGMEM {0}Bitmaps Space char generation -// Char Info: const FONT_CHAR_INFO PROGMEM {0}Descriptors [ ] Generate space bitmap -// Font Info: const FONT_INFO {0}FontInfo [2] pixels for space char -// Width: const uint8_t {0}Width -// Height: const uint8_t {0}Height -// -///////////////////////////////////////////////////////////////////////////////////////////////////// - -#include "Arial.h" - -// -// Font data for Arial 8pt -// - -// Character bitmaps for Arial 8pt -const uint8_t PROGMEM arial_8ptBitmaps [] = -{ - // @0 ' ' (2 pixels wide) - 0x00, 0x00, // - 0x00, 0x00, // - - // @4 '!' (1 pixels wide) - 0x1F, 0xA0, // ###### # - - // @6 '"' (3 pixels wide) - 0x1C, 0x00, // ### - 0x00, 0x00, // - 0x1C, 0x00, // ### - - // @12 '#' (5 pixels wide) - 0x04, 0xE0, // # ### - 0x07, 0x80, // #### - 0x1C, 0xE0, // ### ### - 0x07, 0x80, // #### - 0x1C, 0x80, // ### # - - // @22 '$' (5 pixels wide) - 0x0C, 0x40, // ## # - 0x12, 0x20, // # # # - 0x1F, 0xF0, // ######### - 0x12, 0x20, // # # # - 0x09, 0xC0, // # ### - - // @32 '%' (9 pixels wide) - 0x0C, 0x00, // ## - 0x12, 0x00, // # # - 0x12, 0x20, // # # # - 0x0C, 0xC0, // ## ## - 0x03, 0x00, // ## - 0x0C, 0xC0, // ## ## - 0x11, 0x20, // # # # - 0x01, 0x20, // # # - 0x00, 0xC0, // ## - - // @50 '&' (6 pixels wide) - 0x00, 0xC0, // ## - 0x0D, 0x20, // ## # # - 0x12, 0x20, // # # # - 0x13, 0x20, // # ## # - 0x0C, 0xC0, // ## ## - 0x00, 0xA0, // # # - - // @62 ''' (1 pixels wide) - 0x1C, 0x00, // ### - - // @64 '(' (3 pixels wide) - 0x07, 0xE0, // ###### - 0x08, 0x10, // # # - 0x10, 0x08, // # # - - // @70 ')' (3 pixels wide) - 0x10, 0x08, // # # - 0x08, 0x10, // # # - 0x07, 0xE0, // ###### - - // @76 '*' (3 pixels wide) - 0x0A, 0x00, // # # - 0x1C, 0x00, // ### - 0x0A, 0x00, // # # - - // @82 '+' (5 pixels wide) - 0x01, 0x00, // # - 0x01, 0x00, // # - 0x07, 0xC0, // ##### - 0x01, 0x00, // # - 0x01, 0x00, // # - - // @92 ',' (1 pixels wide) - 0x00, 0x38, // ### - - // @94 '-' (3 pixels wide) - 0x00, 0x80, // # - 0x00, 0x80, // # - 0x00, 0x80, // # - - // @100 '.' (1 pixels wide) - 0x00, 0x20, // # - - // @102 '/' (3 pixels wide) - 0x00, 0x60, // ## - 0x07, 0x80, // #### - 0x18, 0x00, // ## - - // @108 '0' (5 pixels wide) - 0x0F, 0xC0, // ###### - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x0F, 0xC0, // ###### - - // @118 '1' (3 pixels wide) - 0x04, 0x00, // # - 0x08, 0x00, // # - 0x1F, 0xE0, // ######## - - // @124 '2' (5 pixels wide) - 0x08, 0x20, // # # - 0x10, 0x60, // # ## - 0x10, 0xA0, // # # # - 0x11, 0x20, // # # # - 0x0E, 0x20, // ### # - - // @134 '3' (5 pixels wide) - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x0D, 0xC0, // ## ### - - // @144 '4' (5 pixels wide) - 0x01, 0x80, // ## - 0x06, 0x80, // ## # - 0x08, 0x80, // # # - 0x1F, 0xE0, // ######## - 0x00, 0x80, // # - - // @154 '5' (5 pixels wide) - 0x06, 0x40, // ## # - 0x1A, 0x20, // ## # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x11, 0xC0, // # ### - - // @164 '6' (5 pixels wide) - 0x0F, 0xC0, // ###### - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x09, 0xC0, // # ### - - // @174 '7' (5 pixels wide) - 0x10, 0x00, // # - 0x10, 0xE0, // # ### - 0x13, 0x00, // # ## - 0x1C, 0x00, // ### - 0x10, 0x00, // # - - // @184 '8' (5 pixels wide) - 0x0D, 0xC0, // ## ### - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x0D, 0xC0, // ## ### - - // @194 '9' (5 pixels wide) - 0x0E, 0x40, // ### # - 0x11, 0x20, // # # # - 0x11, 0x20, // # # # - 0x11, 0x20, // # # # - 0x0F, 0xC0, // ###### - - // @204 ':' (1 pixels wide) - 0x04, 0x20, // # # - - // @206 ';' (1 pixels wide) - 0x04, 0x38, // # ### - - // @208 '<' (5 pixels wide) - 0x01, 0x00, // # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x04, 0x40, // # # - - // @218 '=' (5 pixels wide) - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - - // @228 '>' (5 pixels wide) - 0x04, 0x40, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x01, 0x00, // # - - // @238 '?' (5 pixels wide) - 0x08, 0x00, // # - 0x10, 0x00, // # - 0x11, 0xA0, // # ## # - 0x12, 0x00, // # # - 0x0C, 0x00, // ## - - // @248 '@' (10 pixels wide) - 0x03, 0xE0, // ##### - 0x0C, 0x10, // ## # - 0x09, 0xC8, // # ### # - 0x12, 0x28, // # # # # - 0x14, 0x28, // # # # # - 0x14, 0x48, // # # # # - 0x13, 0xE8, // # ##### # - 0x16, 0x28, // # ## # # - 0x08, 0x48, // # # # - 0x07, 0x90, // #### # - - // @268 'A' (7 pixels wide) - 0x00, 0x60, // ## - 0x01, 0x80, // ## - 0x0E, 0x80, // ### # - 0x10, 0x80, // # # - 0x0E, 0x80, // ### # - 0x01, 0x80, // ## - 0x00, 0x60, // ## - - // @282 'B' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x0F, 0xC0, // ###### - - // @294 'C' (6 pixels wide) - 0x07, 0x80, // #### - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x08, 0x40, // # # - - // @306 'D' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x08, 0x40, // # # - 0x07, 0x80, // #### - - // @318 'E' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - - // @328 'F' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x12, 0x00, // # # - 0x12, 0x00, // # # - 0x12, 0x00, // # # - 0x10, 0x00, // # - - // @338 'G' (7 pixels wide) - 0x07, 0x80, // #### - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x11, 0x20, // # # # - 0x09, 0x40, // # # # - 0x05, 0x80, // # ## - - // @352 'H' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x1F, 0xE0, // ######## - - // @364 'I' (1 pixels wide) - 0x1F, 0xE0, // ######## - - // @366 'J' (4 pixels wide) - 0x00, 0xC0, // ## - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x1F, 0xC0, // ####### - - // @374 'K' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x01, 0x00, // # - 0x02, 0x00, // # - 0x07, 0x00, // ### - 0x08, 0xC0, // # ## - 0x10, 0x20, // # # - - // @386 'L' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - - // @396 'M' (7 pixels wide) - 0x1F, 0xE0, // ######## - 0x0C, 0x00, // ## - 0x03, 0x80, // ### - 0x00, 0x60, // ## - 0x03, 0x80, // ### - 0x0C, 0x00, // ## - 0x1F, 0xE0, // ######## - - // @410 'N' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x08, 0x00, // # - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x00, 0x40, // # - 0x1F, 0xE0, // ######## - - // @422 'O' (7 pixels wide) - 0x07, 0x80, // #### - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x08, 0x40, // # # - 0x07, 0x80, // #### - - // @436 'P' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x11, 0x00, // # # - 0x11, 0x00, // # # - 0x11, 0x00, // # # - 0x0E, 0x00, // ### - - // @446 'Q' (7 pixels wide) - 0x07, 0x80, // #### - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x10, 0xA0, // # # # - 0x10, 0xA0, // # # # - 0x08, 0x40, // # # - 0x07, 0xA0, // #### # - - // @460 'R' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x12, 0x00, // # # - 0x12, 0x00, // # # - 0x13, 0x00, // # ## - 0x12, 0xC0, // # # ## - 0x0C, 0x20, // ## # - - // @472 'S' (6 pixels wide) - 0x0C, 0x40, // ## # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x11, 0x20, // # # # - 0x11, 0x20, // # # # - 0x08, 0xC0, // # ## - - // @484 'T' (5 pixels wide) - 0x10, 0x00, // # - 0x10, 0x00, // # - 0x1F, 0xE0, // ######## - 0x10, 0x00, // # - 0x10, 0x00, // # - - // @494 'U' (6 pixels wide) - 0x1F, 0xC0, // ####### - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x1F, 0xC0, // ####### - - // @506 'V' (7 pixels wide) - 0x18, 0x00, // ## - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x00, 0x60, // ## - 0x01, 0x80, // ## - 0x06, 0x00, // ## - 0x18, 0x00, // ## - - // @520 'W' (11 pixels wide) - 0x18, 0x00, // ## - 0x07, 0x80, // #### - 0x00, 0x60, // ## - 0x01, 0x80, // ## - 0x0E, 0x00, // ### - 0x10, 0x00, // # - 0x0E, 0x00, // ### - 0x01, 0x80, // ## - 0x00, 0x60, // ## - 0x07, 0x80, // #### - 0x18, 0x00, // ## - - // @542 'X' (6 pixels wide) - 0x10, 0x20, // # # - 0x0C, 0xC0, // ## ## - 0x03, 0x00, // ## - 0x03, 0x00, // ## - 0x0C, 0xC0, // ## ## - 0x10, 0x20, // # # - - // @554 'Y' (7 pixels wide) - 0x10, 0x00, // # - 0x0C, 0x00, // ## - 0x02, 0x00, // # - 0x01, 0xE0, // #### - 0x02, 0x00, // # - 0x0C, 0x00, // ## - 0x10, 0x00, // # - - // @568 'Z' (6 pixels wide) - 0x00, 0x20, // # - 0x10, 0x60, // # ## - 0x11, 0xA0, // # ## # - 0x16, 0x20, // # ## # - 0x18, 0x20, // ## # - 0x10, 0x20, // # # - - // @580 '[' (2 pixels wide) - 0x1F, 0xF8, // ########## - 0x10, 0x08, // # # - - // @584 '\' (3 pixels wide) - 0x18, 0x00, // ## - 0x07, 0x80, // #### - 0x00, 0x60, // ## - - // @590 ']' (2 pixels wide) - 0x10, 0x08, // # # - 0x1F, 0xF8, // ########## - - // @594 '^' (5 pixels wide) - 0x02, 0x00, // # - 0x0C, 0x00, // ## - 0x10, 0x00, // # - 0x0C, 0x00, // ## - 0x02, 0x00, // # - - // @604 '_' (6 pixels wide) - 0x00, 0x08, // # - 0x00, 0x08, // # - 0x00, 0x08, // # - 0x00, 0x08, // # - 0x00, 0x08, // # - 0x00, 0x08, // # - - // @616 '`' (2 pixels wide) - 0x10, 0x00, // # - 0x08, 0x00, // # - - // @620 'a' (5 pixels wide) - 0x02, 0xC0, // # ## - 0x05, 0x20, // # # # - 0x05, 0x20, // # # # - 0x05, 0x40, // # # # - 0x03, 0xE0, // ##### - - // @630 'b' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x02, 0x40, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x03, 0xC0, // #### - - // @640 'c' (5 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x02, 0x40, // # # - - // @650 'd' (5 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x02, 0x40, // # # - 0x1F, 0xE0, // ######## - - // @660 'e' (5 pixels wide) - 0x03, 0xC0, // #### - 0x05, 0x20, // # # # - 0x05, 0x20, // # # # - 0x05, 0x20, // # # # - 0x03, 0x40, // ## # - - // @670 'f' (3 pixels wide) - 0x04, 0x00, // # - 0x0F, 0xE0, // ####### - 0x14, 0x00, // # # - - // @676 'g' (5 pixels wide) - 0x03, 0xC8, // #### # - 0x04, 0x28, // # # # - 0x04, 0x28, // # # # - 0x02, 0x48, // # # # - 0x07, 0xF0, // ####### - - // @686 'h' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x02, 0x00, // # - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x03, 0xE0, // ##### - - // @696 'i' (1 pixels wide) - 0x17, 0xE0, // # ###### - - // @698 'j' (2 pixels wide) - 0x00, 0x08, // # - 0x17, 0xF0, // # ####### - - // @702 'k' (4 pixels wide) - 0x1F, 0xE0, // ######## - 0x01, 0x00, // # - 0x02, 0xC0, // # ## - 0x04, 0x20, // # # - - // @710 'l' (1 pixels wide) - 0x1F, 0xE0, // ######## - - // @712 'm' (7 pixels wide) - 0x07, 0xE0, // ###### - 0x02, 0x00, // # - 0x04, 0x00, // # - 0x07, 0xE0, // ###### - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x03, 0xE0, // ##### - - // @726 'n' (5 pixels wide) - 0x07, 0xE0, // ###### - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x03, 0xE0, // ##### - - // @736 'o' (5 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x03, 0xC0, // #### - - // @746 'p' (5 pixels wide) - 0x07, 0xF8, // ######## - 0x02, 0x40, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x03, 0xC0, // #### - - // @756 'q' (5 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x02, 0x40, // # # - 0x07, 0xF8, // ######## - - // @766 'r' (3 pixels wide) - 0x07, 0xE0, // ###### - 0x02, 0x00, // # - 0x04, 0x00, // # - - // @772 's' (5 pixels wide) - 0x02, 0x40, // # # - 0x05, 0x20, // # # # - 0x05, 0x20, // # # # - 0x04, 0xA0, // # # # - 0x02, 0x40, // # # - - // @782 't' (3 pixels wide) - 0x04, 0x00, // # - 0x1F, 0xE0, // ######## - 0x04, 0x20, // # # - - // @788 'u' (5 pixels wide) - 0x07, 0xC0, // ##### - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x40, // # - 0x07, 0xE0, // ###### - - // @798 'v' (5 pixels wide) - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x00, 0x60, // ## - 0x01, 0x80, // ## - 0x06, 0x00, // ## - - // @808 'w' (9 pixels wide) - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x00, 0x60, // ## - 0x03, 0x80, // ### - 0x04, 0x00, // # - 0x03, 0x80, // ### - 0x00, 0x60, // ## - 0x01, 0x80, // ## - 0x06, 0x00, // ## - - // @826 'x' (5 pixels wide) - 0x04, 0x20, // # # - 0x02, 0x40, // # # - 0x01, 0x80, // ## - 0x02, 0x40, // # # - 0x04, 0x20, // # # - - // @836 'y' (5 pixels wide) - 0x06, 0x00, // ## - 0x01, 0x88, // ## # - 0x00, 0x70, // ### - 0x01, 0x80, // ## - 0x06, 0x00, // ## - - // @846 'z' (5 pixels wide) - 0x04, 0x20, // # # - 0x04, 0x60, // # ## - 0x05, 0xA0, // # ## # - 0x06, 0x20, // ## # - 0x04, 0x20, // # # - - // @856 '{' (3 pixels wide) - 0x01, 0x00, // # - 0x0E, 0xF0, // ### #### - 0x10, 0x08, // # # - - // @862 '|' (1 pixels wide) - 0x1F, 0xF8, // ########## - - // @864 '}' (3 pixels wide) - 0x10, 0x08, // # # - 0x0E, 0xF0, // ### #### - 0x01, 0x00, // # - - // @870 '~' (5 pixels wide) - 0x03, 0x00, // ## - 0x02, 0x00, // # - 0x03, 0x00, // ## - 0x01, 0x00, // # - 0x02, 0x00, // # -}; - -// Character descriptors for Arial 8pt -// { [Char width in bits], [Char height in bits], [Offset into arial_8ptCharBitmaps in bytes] } -const FONT_CHAR_INFO PROGMEM arial_8ptDescriptors[] = -{ - {1, 14, 0}, // ' ' - {1, 14, 4}, // '!' - {3, 14, 6}, // '"' - {5, 14, 12}, // '#' - {5, 14, 22}, // '$' - {9, 14, 32}, // '%' - {6, 14, 50}, // '&' - {1, 14, 62}, // ''' - {3, 14, 64}, // '(' - {3, 14, 70}, // ')' - {3, 14, 76}, // '*' - {5, 14, 82}, // '+' - {1, 14, 92}, // ',' - {3, 14, 94}, // '-' - {1, 14, 100}, // '.' - {3, 14, 102}, // '/' - {5, 14, 108}, // '0' - {3, 14, 118}, // '1' - {5, 14, 124}, // '2' - {5, 14, 134}, // '3' - {5, 14, 144}, // '4' - {5, 14, 154}, // '5' - {5, 14, 164}, // '6' - {5, 14, 174}, // '7' - {5, 14, 184}, // '8' - {5, 14, 194}, // '9' - {1, 14, 204}, // ':' - {1, 14, 206}, // ';' - {5, 14, 208}, // '<' - {5, 14, 218}, // '=' - {5, 14, 228}, // '>' - {5, 14, 238}, // '?' - {10, 14, 248}, // '@' - {7, 14, 268}, // 'A' - {6, 14, 282}, // 'B' - {6, 14, 294}, // 'C' - {6, 14, 306}, // 'D' - {5, 14, 318}, // 'E' - {5, 14, 328}, // 'F' - {7, 14, 338}, // 'G' - {6, 14, 352}, // 'H' - {1, 14, 364}, // 'I' - {4, 14, 366}, // 'J' - {6, 14, 374}, // 'K' - {5, 14, 386}, // 'L' - {7, 14, 396}, // 'M' - {6, 14, 410}, // 'N' - {7, 14, 422}, // 'O' - {5, 14, 436}, // 'P' - {7, 14, 446}, // 'Q' - {6, 14, 460}, // 'R' - {6, 14, 472}, // 'S' - {5, 14, 484}, // 'T' - {6, 14, 494}, // 'U' - {7, 14, 506}, // 'V' - {11, 14, 520}, // 'W' - {6, 14, 542}, // 'X' - {7, 14, 554}, // 'Y' - {6, 14, 568}, // 'Z' - {2, 14, 580}, // '[' - {3, 14, 584}, // '\' - {2, 14, 590}, // ']' - {5, 14, 594}, // '^' - {6, 14, 604}, // '_' - {2, 14, 616}, // '`' - {5, 14, 620}, // 'a' - {5, 14, 630}, // 'b' - {5, 14, 640}, // 'c' - {5, 14, 650}, // 'd' - {5, 14, 660}, // 'e' - {3, 14, 670}, // 'f' - {5, 14, 676}, // 'g' - {5, 14, 686}, // 'h' - {1, 14, 696}, // 'i' - {2, 14, 698}, // 'j' - {4, 14, 702}, // 'k' - {1, 14, 710}, // 'l' - {7, 14, 712}, // 'm' - {5, 14, 726}, // 'n' - {5, 14, 736}, // 'o' - {5, 14, 746}, // 'p' - {5, 14, 756}, // 'q' - {3, 14, 766}, // 'r' - {5, 14, 772}, // 's' - {3, 14, 782}, // 't' - {5, 14, 788}, // 'u' - {5, 14, 798}, // 'v' - {9, 14, 808}, // 'w' - {5, 14, 826}, // 'x' - {5, 14, 836}, // 'y' - {5, 14, 846}, // 'z' - {3, 14, 856}, // '{' - {1, 14, 862}, // '|' - {3, 14, 864}, // '}' - {5, 14, 870}, // '~' -}; - -// Font information for Arial 8pt -const FONT_INFO arial_8ptFontInfo = -{ - 14, // Character height - ' ', // Start character - '~', // End character - 1, - arial_8ptDescriptors, // Character descriptor array - arial_8ptBitmaps, // Character bitmap array -}; - - - -// -// Font data for Arial 7pt -// - -// Character bitmaps for Arial 7pt -const uint8_t PROGMEM arial_7ptBitmaps [] = -{ - // @0 ' ' (2 pixels wide) - 0x00, 0x00, // - 0x00, 0x00, // - - // @4 '!' (1 pixels wide) - 0x3E, 0x80, // ##### # - - // @6 '"' (3 pixels wide) - 0x30, 0x00, // ## - 0x00, 0x00, // - 0x30, 0x00, // ## - - // @12 '#' (4 pixels wide) - 0x0B, 0x80, // # ### - 0x3E, 0x00, // ##### - 0x0B, 0x80, // # ### - 0x3E, 0x00, // ##### - - // @20 '$' (5 pixels wide) - 0x19, 0x00, // ## # - 0x24, 0x80, // # # # - 0x3F, 0xC0, // ######## - 0x24, 0x80, // # # # - 0x13, 0x00, // # ## - - // @30 '%' (6 pixels wide) - 0x10, 0x00, // # - 0x28, 0x00, // # # - 0x13, 0x80, // # ### - 0x1D, 0x00, // ### # - 0x22, 0x80, // # # # - 0x01, 0x00, // # - - // @42 '&' (6 pixels wide) - 0x03, 0x00, // ## - 0x1C, 0x80, // ### # - 0x24, 0x80, // # # # - 0x26, 0x80, // # ## # - 0x39, 0x00, // ### # - 0x02, 0x80, // # # - - // @54 ''' (1 pixels wide) - 0x30, 0x00, // ## - - // @56 '(' (3 pixels wide) - 0x0F, 0x80, // ##### - 0x10, 0x40, // # # - 0x20, 0x20, // # # - - // @62 ')' (3 pixels wide) - 0x20, 0x20, // # # - 0x10, 0x40, // # # - 0x0F, 0x80, // ##### - - // @68 '*' (3 pixels wide) - 0x28, 0x00, // # # - 0x30, 0x00, // ## - 0x28, 0x00, // # # - - // @74 '+' (5 pixels wide) - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x0F, 0x80, // ##### - 0x02, 0x00, // # - 0x02, 0x00, // # - - // @84 ',' (1 pixels wide) - 0x00, 0xC0, // ## - - // @86 '-' (2 pixels wide) - 0x02, 0x00, // # - 0x02, 0x00, // # - - // @90 '.' (1 pixels wide) - 0x00, 0x80, // # - - // @92 '/' (3 pixels wide) - 0x01, 0x80, // ## - 0x0E, 0x00, // ### - 0x30, 0x00, // ## - - // @98 '0' (4 pixels wide) - 0x1F, 0x80, // ###### - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x1F, 0x00, // ##### - - // @106 '1' (2 pixels wide) - 0x10, 0x00, // # - 0x3F, 0x80, // ####### - - // @110 '2' (4 pixels wide) - 0x10, 0x80, // # # - 0x21, 0x80, // # ## - 0x26, 0x80, // # ## # - 0x18, 0x80, // ## # - - // @118 '3' (4 pixels wide) - 0x11, 0x00, // # # - 0x20, 0x80, // # # - 0x24, 0x80, // # # # - 0x1B, 0x00, // ## ## - - // @126 '4' (5 pixels wide) - 0x06, 0x00, // ## - 0x0A, 0x00, // # # - 0x12, 0x00, // # # - 0x3F, 0x80, // ####### - 0x02, 0x00, // # - - // @136 '5' (4 pixels wide) - 0x0D, 0x00, // ## # - 0x38, 0x80, // ### # - 0x28, 0x80, // # # # - 0x27, 0x00, // # ### - - // @144 '6' (4 pixels wide) - 0x1F, 0x00, // ##### - 0x28, 0x80, // # # # - 0x28, 0x80, // # # # - 0x17, 0x00, // # ### - - // @152 '7' (4 pixels wide) - 0x20, 0x00, // # - 0x23, 0x80, // # ### - 0x2C, 0x00, // # ## - 0x30, 0x00, // ## - - // @160 '8' (4 pixels wide) - 0x1B, 0x00, // ## ## - 0x24, 0x80, // # # # - 0x24, 0x80, // # # # - 0x1B, 0x00, // ## ## - - // @168 '9' (4 pixels wide) - 0x1D, 0x00, // ### # - 0x22, 0x80, // # # # - 0x22, 0x80, // # # # - 0x1F, 0x00, // ##### - - // @176 ':' (1 pixels wide) - 0x08, 0x80, // # # - - // @178 ';' (1 pixels wide) - 0x08, 0xC0, // # ## - - // @180 '<' (3 pixels wide) - 0x04, 0x00, // # - 0x0A, 0x00, // # # - 0x11, 0x00, // # # - - // @186 '=' (4 pixels wide) - 0x0A, 0x00, // # # - 0x0A, 0x00, // # # - 0x0A, 0x00, // # # - 0x0A, 0x00, // # # - - // @194 '>' (3 pixels wide) - 0x11, 0x00, // # # - 0x0A, 0x00, // # # - 0x04, 0x00, // # - - // @200 '?' (5 pixels wide) - 0x10, 0x00, // # - 0x20, 0x00, // # - 0x26, 0x80, // # ## # - 0x24, 0x00, // # # - 0x18, 0x00, // ## - - // @210 '@' (8 pixels wide) - 0x0F, 0x80, // ##### - 0x10, 0x40, // # # - 0x27, 0xA0, // # #### # - 0x28, 0xA0, // # # # # - 0x27, 0xA0, // # #### # - 0x2C, 0xA0, // # ## # # - 0x11, 0x40, // # # # - 0x0E, 0x40, // ### # - - // @226 'A' (7 pixels wide) - 0x00, 0x80, // # - 0x07, 0x00, // ### - 0x1A, 0x00, // ## # - 0x22, 0x00, // # # - 0x1A, 0x00, // ## # - 0x07, 0x00, // ### - 0x00, 0x80, // # - - // @240 'B' (4 pixels wide) - 0x3F, 0x80, // ####### - 0x24, 0x80, // # # # - 0x24, 0x80, // # # # - 0x1F, 0x00, // ##### - - // @248 'C' (5 pixels wide) - 0x1F, 0x00, // ##### - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x11, 0x00, // # # - - // @258 'D' (5 pixels wide) - 0x3F, 0x80, // ####### - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x1F, 0x00, // ##### - - // @268 'E' (5 pixels wide) - 0x3F, 0x80, // ####### - 0x24, 0x80, // # # # - 0x24, 0x80, // # # # - 0x24, 0x80, // # # # - 0x24, 0x80, // # # # - - // @278 'F' (4 pixels wide) - 0x3F, 0x80, // ####### - 0x24, 0x00, // # # - 0x24, 0x00, // # # - 0x20, 0x00, // # - - // @286 'G' (5 pixels wide) - 0x1F, 0x00, // ##### - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x24, 0x80, // # # # - 0x17, 0x00, // # ### - - // @296 'H' (5 pixels wide) - 0x3F, 0x80, // ####### - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x3F, 0x80, // ####### - - // @306 'I' (1 pixels wide) - 0x3F, 0x80, // ####### - - // @308 'J' (4 pixels wide) - 0x01, 0x80, // ## - 0x00, 0x80, // # - 0x00, 0x80, // # - 0x3F, 0x00, // ###### - - // @316 'K' (5 pixels wide) - 0x3F, 0x80, // ####### - 0x04, 0x00, // # - 0x0A, 0x00, // # # - 0x11, 0x00, // # # - 0x20, 0x80, // # # - - // @326 'L' (4 pixels wide) - 0x3F, 0x80, // ####### - 0x00, 0x80, // # - 0x00, 0x80, // # - 0x00, 0x80, // # - - // @334 'M' (7 pixels wide) - 0x3F, 0x80, // ####### - 0x18, 0x00, // ## - 0x07, 0x00, // ### - 0x00, 0x80, // # - 0x07, 0x00, // ### - 0x18, 0x00, // ## - 0x3F, 0x80, // ####### - - // @348 'N' (5 pixels wide) - 0x3F, 0x80, // ####### - 0x18, 0x00, // ## - 0x04, 0x00, // # - 0x03, 0x00, // ## - 0x3F, 0x80, // ####### - - // @358 'O' (5 pixels wide) - 0x1F, 0x00, // ##### - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x1F, 0x00, // ##### - - // @368 'P' (4 pixels wide) - 0x3F, 0x80, // ####### - 0x24, 0x00, // # # - 0x24, 0x00, // # # - 0x3C, 0x00, // #### - - // @376 'Q' (5 pixels wide) - 0x1F, 0x00, // ##### - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0x21, 0x80, // # ## - 0x1E, 0x80, // #### # - - // @386 'R' (5 pixels wide) - 0x3F, 0x80, // ####### - 0x24, 0x00, // # # - 0x24, 0x00, // # # - 0x26, 0x00, // # ## - 0x19, 0x80, // ## ## - - // @396 'S' (4 pixels wide) - 0x19, 0x00, // ## # - 0x24, 0x80, // # # # - 0x24, 0x80, // # # # - 0x13, 0x00, // # ## - - // @404 'T' (5 pixels wide) - 0x20, 0x00, // # - 0x20, 0x00, // # - 0x3F, 0x80, // ####### - 0x20, 0x00, // # - 0x20, 0x00, // # - - // @414 'U' (5 pixels wide) - 0x3F, 0x00, // ###### - 0x00, 0x80, // # - 0x00, 0x80, // # - 0x00, 0x80, // # - 0x3F, 0x00, // ###### - - // @424 'V' (7 pixels wide) - 0x30, 0x00, // ## - 0x0C, 0x00, // ## - 0x03, 0x00, // ## - 0x00, 0x80, // # - 0x03, 0x00, // ## - 0x0C, 0x00, // ## - 0x30, 0x00, // ## - - // @438 'W' (9 pixels wide) - 0x30, 0x00, // ## - 0x0F, 0x00, // #### - 0x00, 0x80, // # - 0x1F, 0x00, // ##### - 0x20, 0x00, // # - 0x1F, 0x00, // ##### - 0x00, 0x80, // # - 0x0F, 0x00, // #### - 0x30, 0x00, // ## - - // @456 'X' (5 pixels wide) - 0x20, 0x80, // # # - 0x1B, 0x00, // ## ## - 0x04, 0x00, // # - 0x1B, 0x00, // ## ## - 0x20, 0x80, // # # - - // @466 'Y' (5 pixels wide) - 0x20, 0x00, // # - 0x18, 0x00, // ## - 0x07, 0x80, // #### - 0x18, 0x00, // ## - 0x20, 0x00, // # - - // @476 'Z' (6 pixels wide) - 0x21, 0x80, // # ## - 0x22, 0x80, // # # # - 0x24, 0x80, // # # # - 0x28, 0x80, // # # # - 0x30, 0x80, // ## # - 0x20, 0x80, // # # - - // @488 '[' (2 pixels wide) - 0x3F, 0xE0, // ######### - 0x20, 0x20, // # # - - // @492 '\' (3 pixels wide) - 0x30, 0x00, // ## - 0x0E, 0x00, // ### - 0x01, 0x80, // ## - - // @498 ']' (2 pixels wide) - 0x20, 0x20, // # # - 0x3F, 0xE0, // ######### - - // @502 '^' (3 pixels wide) - 0x18, 0x00, // ## - 0x20, 0x00, // # - 0x18, 0x00, // ## - - // @508 '_' (5 pixels wide) - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - - // @518 '`' (2 pixels wide) - 0x20, 0x00, // # - 0x10, 0x00, // # - - // @522 'a' (4 pixels wide) - 0x09, 0x80, // # ## - 0x0A, 0x80, // # # # - 0x0A, 0x80, // # # # - 0x0F, 0x80, // ##### - - // @530 'b' (4 pixels wide) - 0x3F, 0x80, // ####### - 0x08, 0x80, // # # - 0x08, 0x80, // # # - 0x07, 0x00, // ### - - // @538 'c' (4 pixels wide) - 0x07, 0x00, // ### - 0x08, 0x80, // # # - 0x08, 0x80, // # # - 0x05, 0x00, // # # - - // @546 'd' (4 pixels wide) - 0x07, 0x00, // ### - 0x08, 0x80, // # # - 0x08, 0x80, // # # - 0x3F, 0x80, // ####### - - // @554 'e' (4 pixels wide) - 0x07, 0x00, // ### - 0x0A, 0x80, // # # # - 0x0A, 0x80, // # # # - 0x06, 0x80, // ## # - - // @562 'f' (3 pixels wide) - 0x08, 0x00, // # - 0x1F, 0x80, // ###### - 0x28, 0x00, // # # - - // @568 'g' (4 pixels wide) - 0x07, 0x40, // ### # - 0x08, 0xA0, // # # # - 0x08, 0xA0, // # # # - 0x0F, 0xC0, // ###### - - // @576 'h' (4 pixels wide) - 0x3F, 0x80, // ####### - 0x08, 0x00, // # - 0x08, 0x00, // # - 0x07, 0x80, // #### - - // @584 'i' (1 pixels wide) - 0x2F, 0x80, // # ##### - - // @586 'j' (2 pixels wide) - 0x00, 0x20, // # - 0x2F, 0xC0, // # ###### - - // @590 'k' (4 pixels wide) - 0x3F, 0x80, // ####### - 0x02, 0x00, // # - 0x07, 0x00, // ### - 0x08, 0x80, // # # - - // @598 'l' (1 pixels wide) - 0x3F, 0x80, // ####### - - // @600 'm' (7 pixels wide) - 0x0F, 0x80, // ##### - 0x08, 0x00, // # - 0x08, 0x00, // # - 0x0F, 0x80, // ##### - 0x08, 0x00, // # - 0x08, 0x00, // # - 0x07, 0x80, // #### - - // @614 'n' (4 pixels wide) - 0x0F, 0x80, // ##### - 0x08, 0x00, // # - 0x08, 0x00, // # - 0x07, 0x80, // #### - - // @622 'o' (4 pixels wide) - 0x07, 0x00, // ### - 0x08, 0x80, // # # - 0x08, 0x80, // # # - 0x07, 0x00, // ### - - // @630 'p' (4 pixels wide) - 0x0F, 0xE0, // ####### - 0x08, 0x80, // # # - 0x08, 0x80, // # # - 0x07, 0x00, // ### - - // @638 'q' (4 pixels wide) - 0x07, 0x00, // ### - 0x08, 0x80, // # # - 0x08, 0x80, // # # - 0x0F, 0xE0, // ####### - - // @646 'r' (3 pixels wide) - 0x0F, 0x80, // ##### - 0x08, 0x00, // # - 0x08, 0x00, // # - - // @652 's' (4 pixels wide) - 0x04, 0x80, // # # - 0x0A, 0x80, // # # # - 0x0A, 0x80, // # # # - 0x09, 0x00, // # # - - // @660 't' (3 pixels wide) - 0x08, 0x00, // # - 0x1F, 0x80, // ###### - 0x08, 0x80, // # # - - // @666 'u' (4 pixels wide) - 0x0F, 0x00, // #### - 0x00, 0x80, // # - 0x00, 0x80, // # - 0x0F, 0x80, // ##### - - // @674 'v' (5 pixels wide) - 0x08, 0x00, // # - 0x07, 0x00, // ### - 0x00, 0x80, // # - 0x07, 0x00, // ### - 0x08, 0x00, // # - - // @684 'w' (5 pixels wide) - 0x0F, 0x00, // #### - 0x00, 0x80, // # - 0x0F, 0x00, // #### - 0x00, 0x80, // # - 0x0F, 0x00, // #### - - // @694 'x' (4 pixels wide) - 0x08, 0x80, // # # - 0x07, 0x00, // ### - 0x07, 0x00, // ### - 0x08, 0x80, // # # - - // @702 'y' (5 pixels wide) - 0x08, 0x00, // # - 0x07, 0x20, // ### # - 0x00, 0xC0, // ## - 0x07, 0x00, // ### - 0x08, 0x00, // # - - // @712 'z' (3 pixels wide) - 0x09, 0x80, // # ## - 0x0A, 0x80, // # # # - 0x0C, 0x80, // ## # - - // @718 '{' (3 pixels wide) - 0x02, 0x00, // # - 0x3D, 0xE0, // #### #### - 0x20, 0x20, // # # - - // @724 '|' (1 pixels wide) - 0x3F, 0xC0, // ######## - - // @726 '}' (3 pixels wide) - 0x20, 0x20, // # # - 0x3D, 0xE0, // #### #### - 0x02, 0x00, // # - - // @732 '~' (4 pixels wide) - 0x06, 0x00, // ## - 0x04, 0x00, // # - 0x02, 0x00, // # - 0x06, 0x00, // ## -}; - -// Character descriptors for Arial 7pt -// { [Char width in bits], [Char height in bits], [Offset into arial_7ptCharBitmaps in bytes] } -const FONT_CHAR_INFO PROGMEM arial_7ptDescriptors[] = -{ - {1, 12, 0}, // ' ' - {1, 12, 4}, // '!' - {3, 12, 6}, // '"' - {4, 12, 12}, // '#' - {5, 12, 20}, // '$' - {6, 12, 30}, // '%' - {6, 12, 42}, // '&' - {1, 12, 54}, // ''' - {3, 12, 56}, // '(' - {3, 12, 62}, // ')' - {3, 12, 68}, // '*' - {5, 12, 74}, // '+' - {1, 12, 84}, // ',' - {2, 12, 86}, // '-' - {1, 12, 90}, // '.' - {3, 12, 92}, // '/' - {4, 12, 98}, // '0' - {2, 12, 106}, // '1' - {4, 12, 110}, // '2' - {4, 12, 118}, // '3' - {5, 12, 126}, // '4' - {4, 12, 136}, // '5' - {4, 12, 144}, // '6' - {4, 12, 152}, // '7' - {4, 12, 160}, // '8' - {4, 12, 168}, // '9' - {1, 12, 176}, // ':' - {1, 12, 178}, // ';' - {3, 12, 180}, // '<' - {4, 12, 186}, // '=' - {3, 12, 194}, // '>' - {5, 12, 200}, // '?' - {8, 12, 210}, // '@' - {7, 12, 226}, // 'A' - {4, 12, 240}, // 'B' - {5, 12, 248}, // 'C' - {5, 12, 258}, // 'D' - {5, 12, 268}, // 'E' - {4, 12, 278}, // 'F' - {5, 12, 286}, // 'G' - {5, 12, 296}, // 'H' - {1, 12, 306}, // 'I' - {4, 12, 308}, // 'J' - {5, 12, 316}, // 'K' - {4, 12, 326}, // 'L' - {7, 12, 334}, // 'M' - {5, 12, 348}, // 'N' - {5, 12, 358}, // 'O' - {4, 12, 368}, // 'P' - {5, 12, 376}, // 'Q' - {5, 12, 386}, // 'R' - {4, 12, 396}, // 'S' - {5, 12, 404}, // 'T' - {5, 12, 414}, // 'U' - {7, 12, 424}, // 'V' - {9, 12, 438}, // 'W' - {5, 12, 456}, // 'X' - {5, 12, 466}, // 'Y' - {6, 12, 476}, // 'Z' - {2, 12, 488}, // '[' - {3, 12, 492}, // '\' - {2, 12, 498}, // ']' - {3, 12, 502}, // '^' - {5, 12, 508}, // '_' - {2, 12, 518}, // '`' - {4, 12, 522}, // 'a' - {4, 12, 530}, // 'b' - {4, 12, 538}, // 'c' - {4, 12, 546}, // 'd' - {4, 12, 554}, // 'e' - {3, 12, 562}, // 'f' - {4, 12, 568}, // 'g' - {4, 12, 576}, // 'h' - {1, 12, 584}, // 'i' - {2, 12, 586}, // 'j' - {4, 12, 590}, // 'k' - {1, 12, 598}, // 'l' - {7, 12, 600}, // 'm' - {4, 12, 614}, // 'n' - {4, 12, 622}, // 'o' - {4, 12, 630}, // 'p' - {4, 12, 638}, // 'q' - {3, 12, 646}, // 'r' - {4, 12, 652}, // 's' - {3, 12, 660}, // 't' - {4, 12, 666}, // 'u' - {5, 12, 674}, // 'v' - {5, 12, 684}, // 'w' - {4, 12, 694}, // 'x' - {5, 12, 702}, // 'y' - {3, 12, 712}, // 'z' - {3, 12, 718}, // '{' - {1, 12, 724}, // '|' - {3, 12, 726}, // '}' - {4, 12, 732}, // '~' -}; - - -// Font information for Arial 7pt -const FONT_INFO arial_7ptFontInfo = -{ - 9, // Character height - ' ', // Start character - '~', // End character - 1, // Width, in pixels, of space character - arial_7ptDescriptors, // Character descriptor array - arial_7ptBitmaps, // Character bitmap array -}; - diff --git a/Arduino/BTCDieselHeater/src/fonts/Arial.h b/Arduino/BTCDieselHeater/src/fonts/Arial.h deleted file mode 100644 index 05c50d4..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/Arial.h +++ /dev/null @@ -1,12 +0,0 @@ -#include "../../FontTypes.h" - -// Font data for Arial 8pt -extern const uint8_t PROGMEM arial_8ptBitmaps []; -extern const FONT_INFO arial_8ptFontInfo; -extern const FONT_CHAR_INFO PROGMEM arial_8ptDescriptors[]; - -// Font data for Arial 7pt -extern const uint8_t PROGMEM arial_7ptBitmaps []; -extern const FONT_INFO arial_7ptFontInfo; -extern const FONT_CHAR_INFO PROGMEM arial_7ptDescriptors[]; - diff --git a/Arduino/BTCDieselHeater/src/fonts/FontTypes.h b/Arduino/BTCDieselHeater/src/fonts/FontTypes.h deleted file mode 100644 index 54805b8..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/FontTypes.h +++ /dev/null @@ -1,50 +0,0 @@ -/* - * This file is part of the "bluetoothheater" distribution - * (https://gitlab.com/mrjones.id.au/bluetoothheater) - * - * Copyright (C) 2018 Ray Jones - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -#ifndef __FONT_TYPES_H__ -#define __FONT_TYPES_H__ - -#include - -#ifdef __AVR__ - #include - #include -#else - #define PROGMEM -#endif - - -typedef struct { - uint8_t Width; // Char width in bits - uint8_t Height; - uint16_t Offset; // Offset into bitmap array bytes) -} FONT_CHAR_INFO; - -typedef struct { - uint8_t nBitsPerLine; // Character "height" - uint8_t StartChar; // Start character - uint8_t EndChar; // End character - uint8_t SpaceWidth; - const FONT_CHAR_INFO* pCharInfo; // Character descriptor array - const unsigned char* pBitmaps; // Character bitmap array -} FONT_INFO; - -#endif diff --git a/Arduino/BTCDieselHeater/src/fonts/FranklinGothic.cpp b/Arduino/BTCDieselHeater/src/fonts/FranklinGothic.cpp deleted file mode 100644 index 37978a1..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/FranklinGothic.cpp +++ /dev/null @@ -1,1195 +0,0 @@ - -// -// Font data for Franklin Gothic Medium Cond 8pt -// -// Generated by The Dot Factory: -// http://www.eran.io/the-dot-factory-an-lcd-font-and-image-generator/ -// -///////////////////////////////////////////////////////////////////////////////////////////////////// -// -// Dot Factory Settings -// -// Flip/Rotate Padding Removal Line Wrap Descriptors -// [X] Flip X Height(Y): None (O) At column [X] Generate descriptor array -// [ ] Flip Y Width(X): Tightest ( ) At bitmap Char Width: In Bits -// 90deg Char Height: In Bits -// Font Height: In Bits -// Comments Byte [ ] Multiple descriptor arrays -// [X] Variable Name Bit layout: RowMajor -// [X] BMP visualise [#] Order: MSBfirst Create new when exceeds [80] -// [X] Char descriptor Format: Hex -// Style: Cpp Leading: 0x Image width: In Bits -// Image height: In Bits -// Variable name format -// Bitmaps: const uint8_t PROGMEM {0}Bitmaps Space char generation -// Char Info: const FONT_CHAR_INFO PROGMEM {0}Descriptors [ ] Generate space bitmap -// Font Info: const FONT_INFO {0}FontInfo [2] pixels for space char -// Width: const uint8_t {0}Width -// Height: const uint8_t {0}Height -// -///////////////////////////////////////////////////////////////////////////////////////////////////// - -#include "FranklinGothic.h" - -// Character bitmaps for Franklin Gothic Medium Cond 8pt -const uint8_t PROGMEM franklinGothicMediumCond_8ptBitmaps [] = -{ - // @0 ' ' (2 pixels wide) - 0x00, 0x00, // - 0x00, 0x00, // - - // @4 '!' (1 pixels wide) - 0x0F, 0xD0, // ###### # - - // @6 '"' (3 pixels wide) - 0x0E, 0x00, // ### - 0x00, 0x00, // - 0x0E, 0x00, // ### - - // @12 '#' (6 pixels wide) - 0x02, 0x40, // # # - 0x0F, 0xF0, // ######## - 0x02, 0x40, // # # - 0x02, 0x40, // # # - 0x0F, 0xF0, // ######## - 0x02, 0x40, // # # - - // @24 '$' (5 pixels wide) - 0x03, 0x20, // ## # - 0x04, 0x90, // # # # - 0x0F, 0xF8, // ######### - 0x04, 0x90, // # # # - 0x02, 0x60, // # ## - - // @34 '%' (7 pixels wide) - 0x06, 0x00, // ## - 0x09, 0x10, // # # # - 0x06, 0x60, // ## ## - 0x01, 0x80, // ## - 0x06, 0x60, // ## ## - 0x08, 0x90, // # # # - 0x00, 0x60, // ## - - // @48 '&' (6 pixels wide) - 0x00, 0x60, // ## - 0x06, 0x90, // ## # # - 0x09, 0x90, // # ## # - 0x09, 0x50, // # # # # - 0x06, 0x20, // ## # - 0x00, 0xD0, // ## # - - // @60 ''' (1 pixels wide) - 0x0E, 0x00, // ### - - // @62 '(' (2 pixels wide) - 0x07, 0xF8, // ######## - 0x08, 0x04, // # # - - // @66 ')' (2 pixels wide) - 0x08, 0x04, // # # - 0x07, 0xF8, // ######## - - // @70 '*' (3 pixels wide) - 0x06, 0x00, // ## - 0x0F, 0x00, // #### - 0x06, 0x00, // ## - - // @76 '+' (5 pixels wide) - 0x00, 0x80, // # - 0x00, 0x80, // # - 0x03, 0xE0, // ##### - 0x00, 0x80, // # - 0x00, 0x80, // # - - // @86 ',' (1 pixels wide) - 0x00, 0x1C, // ### - - // @88 '-' (2 pixels wide) - 0x00, 0x40, // # - 0x00, 0x40, // # - - // @92 '.' (1 pixels wide) - 0x00, 0x10, // # - - // @94 '/' (5 pixels wide) - 0x00, 0x04, // # - 0x00, 0x38, // ### - 0x00, 0xC0, // ## - 0x07, 0x00, // ### - 0x08, 0x00, // # - - // @104 '0' (5 pixels wide) - 0x07, 0xE0, // ###### - 0x08, 0x10, // # # - 0x08, 0x10, // # # - 0x08, 0x10, // # # - 0x07, 0xE0, // ###### - - // @114 '1' (3 pixels wide) - 0x04, 0x10, // # # - 0x0F, 0xF0, // ######## - 0x00, 0x10, // # - - // @120 '2' (5 pixels wide) - 0x04, 0x10, // # # - 0x08, 0x30, // # ## - 0x08, 0x50, // # # # - 0x08, 0x90, // # # # - 0x07, 0x10, // ### # - - // @130 '3' (5 pixels wide) - 0x04, 0x20, // # # - 0x08, 0x10, // # # - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x06, 0xE0, // ## ### - - // @140 '4' (6 pixels wide) - 0x00, 0xC0, // ## - 0x01, 0x40, // # # - 0x02, 0x40, // # # - 0x04, 0x40, // # # - 0x0F, 0xF0, // ######## - 0x00, 0x40, // # - - // @152 '5' (5 pixels wide) - 0x0F, 0xA0, // ##### # - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x08, 0xE0, // # ### - - // @162 '6' (5 pixels wide) - 0x07, 0xE0, // ###### - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x04, 0xE0, // # ### - - // @172 '7' (5 pixels wide) - 0x08, 0x00, // # - 0x08, 0x00, // # - 0x08, 0xF0, // # #### - 0x0B, 0x00, // # ## - 0x0C, 0x00, // ## - - // @182 '8' (5 pixels wide) - 0x06, 0xE0, // ## ### - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x06, 0xE0, // ## ### - - // @192 '9' (5 pixels wide) - 0x07, 0x20, // ### # - 0x08, 0x90, // # # # - 0x08, 0x90, // # # # - 0x08, 0x90, // # # # - 0x07, 0xE0, // ###### - - // @202 ':' (1 pixels wide) - 0x02, 0x10, // # # - - // @204 ';' (1 pixels wide) - 0x02, 0x1C, // # ### - - // @206 '<' (5 pixels wide) - 0x01, 0x80, // ## - 0x01, 0x80, // ## - 0x02, 0x40, // # # - 0x02, 0x40, // # # - 0x04, 0x20, // # # - - // @216 '=' (4 pixels wide) - 0x01, 0x40, // # # - 0x01, 0x40, // # # - 0x01, 0x40, // # # - 0x01, 0x40, // # # - - // @224 '>' (5 pixels wide) - 0x04, 0x20, // # # - 0x02, 0x40, // # # - 0x02, 0x40, // # # - 0x01, 0x80, // ## - 0x01, 0x80, // ## - - // @234 '?' (4 pixels wide) - 0x06, 0x00, // ## - 0x08, 0xD0, // # ## # - 0x09, 0x00, // # # - 0x06, 0x00, // ## - - // @242 '@' (7 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x09, 0x90, // # ## # - 0x0A, 0x50, // # # # # - 0x0B, 0x90, // # ### # - 0x08, 0x40, // # # - 0x07, 0x80, // #### - - // @256 'A' (5 pixels wide) - 0x00, 0x70, // ### - 0x03, 0xC0, // #### - 0x0C, 0x40, // ## # - 0x03, 0xC0, // #### - 0x00, 0x70, // ### - - // @266 'B' (5 pixels wide) - 0x0F, 0xF0, // ######## - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x06, 0xE0, // ## ### - - // @276 'C' (5 pixels wide) - 0x07, 0xE0, // ###### - 0x08, 0x10, // # # - 0x08, 0x10, // # # - 0x08, 0x10, // # # - 0x06, 0x60, // ## ## - - // @286 'D' (5 pixels wide) - 0x0F, 0xF0, // ######## - 0x08, 0x10, // # # - 0x08, 0x10, // # # - 0x04, 0x20, // # # - 0x03, 0xC0, // #### - - // @296 'E' (4 pixels wide) - 0x0F, 0xF0, // ######## - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x08, 0x10, // # # - - // @304 'F' (4 pixels wide) - 0x0F, 0xF0, // ######## - 0x09, 0x00, // # # - 0x09, 0x00, // # # - 0x08, 0x00, // # - - // @312 'G' (5 pixels wide) - 0x07, 0xE0, // ###### - 0x08, 0x10, // # # - 0x08, 0x10, // # # - 0x08, 0x90, // # # # - 0x06, 0xF0, // ## #### - - // @322 'H' (5 pixels wide) - 0x0F, 0xF0, // ######## - 0x01, 0x00, // # - 0x01, 0x00, // # - 0x01, 0x00, // # - 0x0F, 0xF0, // ######## - - // @332 'I' (1 pixels wide) - 0x0F, 0xF0, // ######## - - // @334 'J' (2 pixels wide) - 0x00, 0x10, // # - 0x0F, 0xF0, // ######## - - // @338 'K' (5 pixels wide) - 0x0F, 0xF0, // ######## - 0x01, 0x00, // # - 0x03, 0x80, // ### - 0x04, 0x60, // # ## - 0x08, 0x10, // # # - - // @348 'L' (4 pixels wide) - 0x0F, 0xF0, // ######## - 0x00, 0x10, // # - 0x00, 0x10, // # - 0x00, 0x10, // # - - // @356 'M' (7 pixels wide) - 0x0F, 0xF0, // ######## - 0x0C, 0x00, // ## - 0x03, 0xC0, // #### - 0x00, 0x30, // ## - 0x03, 0xC0, // #### - 0x0C, 0x00, // ## - 0x0F, 0xF0, // ######## - - // @370 'N' (5 pixels wide) - 0x0F, 0xF0, // ######## - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x00, 0x60, // ## - 0x0F, 0xF0, // ######## - - // @380 'O' (5 pixels wide) - 0x07, 0xE0, // ###### - 0x08, 0x10, // # # - 0x08, 0x10, // # # - 0x08, 0x10, // # # - 0x07, 0xE0, // ###### - - // @390 'P' (4 pixels wide) - 0x0F, 0xF0, // ######## - 0x08, 0x80, // # # - 0x08, 0x80, // # # - 0x07, 0x00, // ### - - // @398 'Q' (5 pixels wide) - 0x07, 0xE0, // ###### - 0x08, 0x10, // # # - 0x08, 0x18, // # ## - 0x08, 0x14, // # # # - 0x07, 0xE4, // ###### # - - // @408 'R' (5 pixels wide) - 0x0F, 0xF0, // ######## - 0x08, 0x80, // # # - 0x08, 0xC0, // # ## - 0x08, 0xA0, // # # # - 0x07, 0x10, // ### # - - // @418 'S' (5 pixels wide) - 0x06, 0x20, // ## # - 0x09, 0x10, // # # # - 0x09, 0x10, // # # # - 0x08, 0x90, // # # # - 0x04, 0x60, // # ## - - // @428 'T' (5 pixels wide) - 0x08, 0x00, // # - 0x08, 0x00, // # - 0x0F, 0xF0, // ######## - 0x08, 0x00, // # - 0x08, 0x00, // # - - // @438 'U' (5 pixels wide) - 0x0F, 0xE0, // ####### - 0x00, 0x10, // # - 0x00, 0x10, // # - 0x00, 0x10, // # - 0x0F, 0xE0, // ####### - - // @448 'V' (5 pixels wide) - 0x0C, 0x00, // ## - 0x03, 0xE0, // ##### - 0x00, 0x10, // # - 0x03, 0xE0, // ##### - 0x0C, 0x00, // ## - - // @458 'W' (7 pixels wide) - 0x0F, 0x80, // ##### - 0x00, 0x70, // ### - 0x03, 0x80, // ### - 0x0C, 0x00, // ## - 0x03, 0xC0, // #### - 0x00, 0x70, // ### - 0x0F, 0x80, // ##### - - // @472 'X' (5 pixels wide) - 0x08, 0x10, // # # - 0x06, 0x60, // ## ## - 0x01, 0x80, // ## - 0x06, 0x60, // ## ## - 0x08, 0x10, // # # - - // @482 'Y' (5 pixels wide) - 0x08, 0x00, // # - 0x06, 0x00, // ## - 0x01, 0xF0, // ##### - 0x06, 0x00, // ## - 0x08, 0x00, // # - - // @492 'Z' (4 pixels wide) - 0x08, 0x30, // # ## - 0x08, 0xD0, // # ## # - 0x0B, 0x10, // # ## # - 0x0C, 0x10, // ## # - - // @500 '[' (2 pixels wide) - 0x0F, 0xFC, // ########## - 0x08, 0x04, // # # - - // @504 '\' (4 pixels wide) - 0x04, 0x00, // # - 0x03, 0x80, // ### - 0x00, 0x70, // ### - 0x00, 0x0C, // ## - - // @512 ']' (2 pixels wide) - 0x08, 0x04, // # # - 0x0F, 0xFC, // ########## - - // @516 '^' (5 pixels wide) - 0x00, 0x80, // # - 0x03, 0x00, // ## - 0x04, 0x00, // # - 0x03, 0x00, // ## - 0x00, 0x80, // # - - // @526 '_' (6 pixels wide) - 0x00, 0x04, // # - 0x00, 0x04, // # - 0x00, 0x04, // # - 0x00, 0x04, // # - 0x00, 0x04, // # - 0x00, 0x04, // # - - // @538 '`' (2 pixels wide) - 0x10, 0x00, // # - 0x08, 0x00, // # - - // @542 'a' (4 pixels wide) - 0x00, 0x60, // ## - 0x02, 0x90, // # # # - 0x02, 0x90, // # # # - 0x01, 0xF0, // ##### - - // @550 'b' (4 pixels wide) - 0x0F, 0xF0, // ######## - 0x02, 0x10, // # # - 0x02, 0x10, // # # - 0x01, 0xE0, // #### - - // @558 'c' (4 pixels wide) - 0x01, 0xE0, // #### - 0x02, 0x10, // # # - 0x02, 0x10, // # # - 0x01, 0x20, // # # - - // @566 'd' (4 pixels wide) - 0x01, 0xE0, // #### - 0x02, 0x10, // # # - 0x02, 0x10, // # # - 0x0F, 0xF0, // ######## - - // @574 'e' (4 pixels wide) - 0x01, 0xE0, // #### - 0x02, 0x90, // # # # - 0x02, 0x90, // # # # - 0x01, 0xA0, // ## # - - // @582 'f' (3 pixels wide) - 0x02, 0x00, // # - 0x07, 0xF0, // ####### - 0x0A, 0x00, // # # - - // @588 'g' (5 pixels wide) - 0x01, 0xA8, // ## # # - 0x02, 0x54, // # # # # - 0x02, 0x54, // # # # # - 0x03, 0x94, // ### # # - 0x04, 0x08, // # # - - // @598 'h' (4 pixels wide) - 0x0F, 0xF0, // ######## - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x01, 0xF0, // ##### - - // @606 'i' (1 pixels wide) - 0x0B, 0xF0, // # ###### - - // @608 'j' (2 pixels wide) - 0x00, 0x04, // # - 0x0B, 0xFC, // # ######## - - // @612 'k' (4 pixels wide) - 0x0F, 0xF0, // ######## - 0x00, 0x80, // # - 0x01, 0x60, // # ## - 0x02, 0x10, // # # - - // @620 'l' (1 pixels wide) - 0x0F, 0xF0, // ######## - - // @622 'm' (7 pixels wide) - 0x03, 0xF0, // ###### - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x01, 0xF0, // ##### - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x01, 0xF0, // ##### - - // @636 'n' (4 pixels wide) - 0x03, 0xF0, // ###### - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x01, 0xF0, // ##### - - // @644 'o' (4 pixels wide) - 0x01, 0xE0, // #### - 0x02, 0x10, // # # - 0x02, 0x10, // # # - 0x01, 0xE0, // #### - - // @652 'p' (4 pixels wide) - 0x03, 0xFC, // ######## - 0x02, 0x10, // # # - 0x02, 0x10, // # # - 0x01, 0xE0, // #### - - // @660 'q' (4 pixels wide) - 0x01, 0xE0, // #### - 0x02, 0x10, // # # - 0x02, 0x10, // # # - 0x03, 0xFC, // ######## - - // @668 'r' (3 pixels wide) - 0x03, 0xF0, // ###### - 0x01, 0x00, // # - 0x02, 0x00, // # - - // @674 's' (3 pixels wide) - 0x01, 0x10, // # # - 0x02, 0x90, // # # # - 0x02, 0x60, // # ## - - // @680 't' (3 pixels wide) - 0x02, 0x00, // # - 0x0F, 0xF0, // ######## - 0x02, 0x10, // # # - - // @686 'u' (4 pixels wide) - 0x03, 0xE0, // ##### - 0x00, 0x10, // # - 0x00, 0x20, // # - 0x03, 0xF0, // ###### - - // @694 'v' (5 pixels wide) - 0x02, 0x00, // # - 0x01, 0xC0, // ### - 0x00, 0x30, // ## - 0x01, 0xC0, // ### - 0x02, 0x00, // # - - // @704 'w' (5 pixels wide) - 0x03, 0xC0, // #### - 0x00, 0x30, // ## - 0x03, 0xC0, // #### - 0x00, 0x30, // ## - 0x03, 0xC0, // #### - - // @714 'x' (3 pixels wide) - 0x03, 0x30, // ## ## - 0x00, 0xC0, // ## - 0x03, 0x30, // ## ## - - // @720 'y' (3 pixels wide) - 0x03, 0xC4, // #### # - 0x00, 0x38, // ### - 0x03, 0xC0, // #### - - // @726 'z' (3 pixels wide) - 0x02, 0x30, // # ## - 0x02, 0xD0, // # ## # - 0x03, 0x10, // ## # - - // @732 '{' (3 pixels wide) - 0x00, 0x40, // # - 0x0F, 0xBC, // ##### #### - 0x08, 0x04, // # # - - // @738 '|' (1 pixels wide) - 0x0F, 0xFC, // ########## - - // @740 '}' (3 pixels wide) - 0x08, 0x04, // # # - 0x0F, 0xBC, // ##### #### - 0x00, 0x40, // # - - // @746 '~' (5 pixels wide) - 0x00, 0x40, // # - 0x00, 0x80, // # - 0x00, 0xC0, // ## - 0x00, 0x40, // # - 0x00, 0x80, // # -}; - -// Character descriptors for Franklin Gothic Medium Cond 8pt -// { [Char width in bits], [Char height in bits], [Offset into franklinGothicMediumCond_8ptCharBitmaps in bytes] } -const FONT_CHAR_INFO PROGMEM franklinGothicMediumCond_8ptDescriptors[] = -{ - {1, 15, 0}, // - {1, 15, 4}, // ! - {3, 15, 6}, // " - {6, 15, 12}, // # - {5, 15, 24}, // $ - {7, 15, 34}, // % - {6, 15, 48}, // & - {1, 15, 60}, // ' - {2, 15, 62}, // ( - {2, 15, 66}, // ) - {3, 15, 70}, // * - {5, 15, 76}, // + - {1, 15, 86}, // , - {2, 15, 88}, // - - {1, 15, 92}, // . - {5, 15, 94}, // / - {5, 15, 104}, // 0 - {3, 15, 114}, // 1 - {5, 15, 120}, // 2 - {5, 15, 130}, // 3 - {6, 15, 140}, // 4 - {5, 15, 152}, // 5 - {5, 15, 162}, // 6 - {5, 15, 172}, // 7 - {5, 15, 182}, // 8 - {5, 15, 192}, // 9 - {1, 15, 202}, // : - {1, 15, 204}, // ; - {5, 15, 206}, // < - {4, 15, 216}, // = - {5, 15, 224}, // > - {4, 15, 234}, // ? - {7, 15, 242}, // @ - {5, 15, 256}, // A - {5, 15, 266}, // B - {5, 15, 276}, // C - {5, 15, 286}, // D - {4, 15, 296}, // E - {4, 15, 304}, // F - {5, 15, 312}, // G - {5, 15, 322}, // H - {1, 15, 332}, // I - {2, 15, 334}, // J - {5, 15, 338}, // K - {4, 15, 348}, // L - {7, 15, 356}, // M - {5, 15, 370}, // N - {5, 15, 380}, // O - {4, 15, 390}, // P - {5, 15, 398}, // Q - {5, 15, 408}, // R - {5, 15, 418}, // S - {5, 15, 428}, // T - {5, 15, 438}, // U - {5, 15, 448}, // V - {7, 15, 458}, // W - {5, 15, 472}, // X - {5, 15, 482}, // Y - {4, 15, 492}, // Z - {2, 15, 500}, // [ - {4, 15, 504}, // \ . - {2, 15, 512}, // ] - {5, 15, 516}, // ^ - {6, 15, 526}, // _ - {2, 15, 538}, // ` - {4, 15, 542}, // a - {4, 15, 550}, // b - {4, 15, 558}, // c - {4, 15, 566}, // d - {4, 15, 574}, // e - {3, 15, 582}, // f - {5, 15, 588}, // g - {4, 15, 598}, // h - {1, 15, 606}, // i - {2, 15, 608}, // j - {4, 15, 612}, // k - {1, 15, 620}, // l - {7, 15, 622}, // m - {4, 15, 636}, // n - {4, 15, 644}, // o - {4, 15, 652}, // p - {4, 15, 660}, // q - {3, 15, 668}, // r - {3, 15, 674}, // s - {3, 15, 680}, // t - {4, 15, 686}, // u - {5, 15, 694}, // v - {5, 15, 704}, // w - {3, 15, 714}, // x - {3, 15, 720}, // y - {3, 15, 726}, // z - {3, 15, 732}, // { - {1, 15, 738}, // | - {3, 15, 740}, // } - {5, 15, 746}, // ~ -}; - - -// Font information for Franklin Gothic Medium Cond 8pt -const FONT_INFO franklinGothicMediumCond_8ptFontInfo = -{ - 15, // Character height - ' ', // Start character - 'z', // End character - 1, // Width, in pixels, of space character - franklinGothicMediumCond_8ptDescriptors, // Character descriptor array - franklinGothicMediumCond_8ptBitmaps, // Character bitmap array -}; - -// -// Font data for Franklin Gothic Medium Cond 7pt -// - -// Character bitmaps for Franklin Gothic Medium Cond 7pt -const uint8_t PROGMEM franklinGothicMediumCond_7ptBitmaps [] = -{ - // @0 ' ' (2 pixels wide) - 0x00, 0x00, // - 0x00, 0x00, // - - // @4 ',' (1 pixels wide) - 0xC0, // ## - - // @5 '.' (1 pixels wide) - 0x80, // # - - // @6 '/' (4 pixels wide) - 0x01, // # - 0x0E, // ### - 0x70, // ### - 0x80, // # - - // @10 '0' (4 pixels wide) - 0x78, // #### - 0x84, // # # - 0x84, // # # - 0x78, // #### - - // @14 '1' (3 pixels wide) - 0x44, // # # - 0xFC, // ###### - 0x04, // # - - // @17 '2' (4 pixels wide) - 0x44, // # # - 0x8C, // # ## - 0x94, // # # # - 0x64, // ## # - - // @21 '3' (4 pixels wide) - 0x48, // # # - 0x84, // # # - 0xA4, // # # # - 0x58, // # ## - - // @25 '4' (5 pixels wide) - 0x18, // ## - 0x68, // ## # - 0x88, // # # - 0xFC, // ###### - 0x08, // # - - // @30 '5' (4 pixels wide) - 0xE8, // ### # - 0xA4, // # # # - 0xA4, // # # # - 0x98, // # ## - - // @34 '6' (4 pixels wide) - 0x78, // #### - 0xA4, // # # # - 0xA4, // # # # - 0x18, // ## - - // @38 '7' (4 pixels wide) - 0x80, // # - 0x9C, // # ### - 0xA0, // # # - 0xC0, // ## - - // @42 '8' (4 pixels wide) - 0x58, // # ## - 0xA4, // # # # - 0xA4, // # # # - 0x58, // # ## - - // @46 '9' (4 pixels wide) - 0x60, // ## - 0x94, // # # # - 0x94, // # # # - 0x78, // #### - - // @50 ':' (1 pixels wide) - 0x88, // # # - - // @51 'A' (3 pixels wide) - 0x3C, // #### - 0xC8, // ## # - 0x3C, // #### - - // @54 'B' (4 pixels wide) - 0xFC, // ###### - 0xA4, // # # # - 0xA4, // # # # - 0x58, // # ## - - // @58 'C' (4 pixels wide) - 0x78, // #### - 0x84, // # # - 0x84, // # # - 0x48, // # # - - // @62 'D' (4 pixels wide) - 0xFC, // ###### - 0x84, // # # - 0x84, // # # - 0x78, // #### - - // @66 'E' (3 pixels wide) - 0xFC, // ###### - 0xA4, // # # # - 0xA4, // # # # - - // @69 'F' (3 pixels wide) - 0xFC, // ###### - 0x90, // # # - 0x90, // # # - - // @72 'G' (4 pixels wide) - 0x78, // #### - 0x84, // # # - 0x94, // # # # - 0x5C, // # ### - - // @76 'H' (4 pixels wide) - 0xFC, // ###### - 0x20, // # - 0x20, // # - 0xFC, // ###### - - // @80 'I' (1 pixels wide) - 0xFC, // ###### - - // @81 'J' (2 pixels wide) - 0x04, // # - 0xFC, // ###### - - // @83 'K' (4 pixels wide) - 0xFC, // ###### - 0x20, // # - 0x58, // # ## - 0x84, // # # - - // @87 'L' (3 pixels wide) - 0xFC, // ###### - 0x04, // # - 0x04, // # - - // @90 'M' (5 pixels wide) - 0xFC, // ###### - 0x60, // ## - 0x1C, // ### - 0x60, // ## - 0xFC, // ###### - - // @95 'N' (4 pixels wide) - 0xFC, // ###### - 0x60, // ## - 0x18, // ## - 0xFC, // ###### - - // @99 'O' (4 pixels wide) - 0x78, // #### - 0x84, // # # - 0x84, // # # - 0x78, // #### - - // @103 'P' (3 pixels wide) - 0xFC, // ###### - 0x90, // # # - 0x60, // ## - - // @106 'Q' (4 pixels wide) - 0x78, // #### - 0x84, // # # - 0x86, // # ## - 0x7A, // #### # - - // @110 'R' (4 pixels wide) - 0xFC, // ###### - 0x90, // # # - 0x98, // # ## - 0x64, // ## # - - // @114 'S' (4 pixels wide) - 0x48, // # # - 0xA4, // # # # - 0x94, // # # # - 0x48, // # # - - // @118 'T' (3 pixels wide) - 0x80, // # - 0xFC, // ###### - 0x80, // # - - // @121 'U' (4 pixels wide) - 0xF8, // ##### - 0x04, // # - 0x04, // # - 0xF8, // ##### - - // @125 'V' (3 pixels wide) - 0xF0, // #### - 0x0C, // ## - 0xF0, // #### - - // @128 'W' (5 pixels wide) - 0xF0, // #### - 0x0C, // ## - 0xF0, // #### - 0x0C, // ## - 0xF0, // #### - - // @133 'X' (3 pixels wide) - 0xCC, // ## ## - 0x30, // ## - 0xCC, // ## ## - - // @136 'Y' (5 pixels wide) - 0x80, // # - 0x60, // ## - 0x1C, // ### - 0x60, // ## - 0x80, // # - - // @141 'Z' (3 pixels wide) - 0x8C, // # ## - 0xB4, // # ## # - 0xC4, // ## # - - // @144 '\' (4 pixels wide) - 0x80, // # - 0x70, // ### - 0x0C, // ## - 0x03, // ## - - // @148 '`' (2 pixels wide) - 0x80, // # - 0x40, // # - - // @150 'a' (3 pixels wide) - 0x90, // # # - 0xA8, // # # # - 0x78, // #### - - // @153 'b' (3 pixels wide) - 0xFC, // ###### - 0x44, // # # - 0x38, // ### - - // @156 'c' (3 pixels wide) - 0x70, // ### - 0x88, // # # - 0x50, // # # - - // @159 'd' (3 pixels wide) - 0x38, // ### - 0x44, // # # - 0xFC, // ###### - - // @162 'e' (3 pixels wide) - 0x70, // ### - 0xA8, // # # # - 0x68, // ## # - - // @165 'f' (2 pixels wide) - 0x7C, // ##### - 0xA0, // # # - - // @167 'g' (4 pixels wide) - 0x2A, // # # # - 0x55, // # # # # - 0x65, // ## # # - 0x82, // # # - - // @171 'h' (3 pixels wide) - 0xFC, // ###### - 0x40, // # - 0x3C, // #### - - // @174 'i' (1 pixels wide) - 0xBE, // # ##### - - // @175 'j' (2 pixels wide) - 0x00, 0x80, // # - 0xBF, 0x80, // # ####### - - // @179 'k' (3 pixels wide) - 0xFC, // ###### - 0x30, // ## - 0x4C, // # ## - - // @182 'l' (1 pixels wide) - 0xFC, // ###### - - // @183 'm' (5 pixels wide) - 0xF8, // ##### - 0x80, // # - 0xF8, // ##### - 0x80, // # - 0x78, // #### - - // @188 'n' (3 pixels wide) - 0xF8, // ##### - 0x80, // # - 0x78, // #### - - // @191 'o' (3 pixels wide) - 0x70, // ### - 0x88, // # # - 0x70, // ### - - // @194 'p' (3 pixels wide) - 0xFE, // ####### - 0x88, // # # - 0x70, // ### - - // @197 'q' (3 pixels wide) - 0x70, // ### - 0x88, // # # - 0xFE, // ####### - - // @200 'r' (3 pixels wide) - 0xF8, // ##### - 0x40, // # - 0x80, // # - - // @203 's' (3 pixels wide) - 0x48, // # # - 0xA8, // # # # - 0x90, // # # - - // @206 't' (2 pixels wide) - 0xFC, // ###### - 0x44, // # # - - // @208 'u' (3 pixels wide) - 0xF0, // #### - 0x08, // # - 0xF8, // ##### - - // @211 'v' (3 pixels wide) - 0xE0, // ### - 0x18, // ## - 0xE0, // ### - - // @214 'w' (5 pixels wide) - 0xE0, // ### - 0x18, // ## - 0xE0, // ### - 0x18, // ## - 0xE0, // ### - - // @219 'x' (3 pixels wide) - 0x88, // # # - 0x70, // ### - 0x88, // # # - - // @222 'y' (3 pixels wide) - 0xE2, // ### # - 0x1C, // ### - 0xE0, // ### - - // @225 'z' (2 pixels wide) - 0xB8, // # ### - 0xC8, // ## # -}; - -// Character descriptors for Franklin Gothic Medium Cond 7pt -// { [Char width in bits], [Char height in bits], [Offset into franklinGothicMediumCond_7ptCharBitmaps in bytes] } -const FONT_CHAR_INFO PROGMEM franklinGothicMediumCond_7ptDescriptors[] = -{ - {1, 7, 0}, // - {0, 0, 0}, // ! - {0, 0, 0}, // " - {0, 0, 0}, // # - {0, 0, 0}, // $ - {0, 0, 0}, // % - {0, 0, 0}, // & - {0, 0, 0}, // ' - {0, 0, 0}, // ( - {0, 0, 0}, // ) - {0, 0, 0}, // * - {0, 0, 0}, // + - {1, 2, 4}, // , - {0, 0, 0}, // - - {1, 1, 5}, // . - {4, 8, 6}, // / - {4, 6, 10}, // 0 - {3, 6, 14}, // 1 - {4, 6, 17}, // 2 - {4, 6, 21}, // 3 - {5, 6, 25}, // 4 - {4, 6, 30}, // 5 - {4, 6, 34}, // 6 - {4, 6, 38}, // 7 - {4, 6, 42}, // 8 - {4, 6, 46}, // 9 - {1, 5, 50}, // : - {0, 0, 0}, // ; - {0, 0, 0}, // < - {0, 0, 0}, // = - {0, 0, 0}, // > - {0, 0, 0}, // ? - {0, 0, 0}, // @ - {3, 6, 51}, // A - {4, 6, 54}, // B - {4, 6, 58}, // C - {4, 6, 62}, // D - {3, 6, 66}, // E - {3, 6, 69}, // F - {4, 6, 72}, // G - {4, 6, 76}, // H - {1, 6, 80}, // I - {2, 6, 81}, // J - {4, 6, 83}, // K - {3, 6, 87}, // L - {5, 6, 90}, // M - {4, 6, 95}, // N - {4, 6, 99}, // O - {3, 6, 103}, // P - {4, 7, 106}, // Q - {4, 6, 110}, // R - {4, 6, 114}, // S - {3, 6, 118}, // T - {4, 6, 121}, // U - {3, 6, 125}, // V - {5, 6, 128}, // W - {3, 6, 133}, // X - {5, 6, 136}, // Y - {3, 6, 141}, // Z - {0, 0, 0}, // [ - {4, 8, 144}, // \ . - {0, 0, 0}, // ] - {0, 0, 0}, // ^ - {0, 0, 0}, // _ - {2, 2, 148}, // ` - {3, 5, 150}, // a - {3, 6, 153}, // b - {3, 5, 156}, // c - {3, 6, 159}, // d - {3, 5, 162}, // e - {2, 6, 165}, // f - {4, 8, 167}, // g - {3, 6, 171}, // h - {1, 7, 174}, // i - {2, 9, 175}, // j - {3, 6, 179}, // k - {1, 6, 182}, // l - {5, 5, 183}, // m - {3, 5, 188}, // n - {3, 5, 191}, // o - {3, 7, 194}, // p - {3, 7, 197}, // q - {3, 5, 200}, // r - {3, 5, 203}, // s - {2, 6, 206}, // t - {3, 5, 208}, // u - {3, 5, 211}, // v - {5, 5, 214}, // w - {3, 5, 219}, // x - {3, 7, 222}, // y - {2, 5, 225}, // z -}; - -// Font information for Franklin Gothic Medium Cond 7pt -const FONT_INFO franklinGothicMediumCond_7ptFontInfo = -{ - 12, // Character height - ' ', // Start character - 'z', // End character - 1, // width of space - franklinGothicMediumCond_7ptDescriptors, // Character descriptor array - franklinGothicMediumCond_7ptBitmaps, // Character bitmap array -}; - diff --git a/Arduino/BTCDieselHeater/src/fonts/FranklinGothic.h b/Arduino/BTCDieselHeater/src/fonts/FranklinGothic.h deleted file mode 100644 index f79ef14..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/FranklinGothic.h +++ /dev/null @@ -1,14 +0,0 @@ -#include "FontTypes.h" - -// Font data for Franklin Gothic Medium Cond 8pt -extern const uint8_t PROGMEM franklinGothicMediumCond_8ptBitmaps [] ; -extern const FONT_CHAR_INFO PROGMEM franklinGothicMediumCond_8ptDescriptors[] ; -extern const FONT_INFO franklinGothicMediumCond_8ptFontInfo; - -// Font data for Franklin Gothic Medium Cond 7pt -extern const uint8_t PROGMEM franklinGothicMediumCond_7ptBitmaps []; -extern const FONT_INFO franklinGothicMediumCond_7ptFontInfo; -extern const FONT_CHAR_INFO PROGMEM franklinGothicMediumCond_7ptDescriptors[]; - - - diff --git a/Arduino/BTCDieselHeater/src/fonts/Icons.cpp b/Arduino/BTCDieselHeater/src/fonts/Icons.cpp deleted file mode 100644 index 687c7c6..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/Icons.cpp +++ /dev/null @@ -1,134 +0,0 @@ -/* - * This file is part of the "bluetoothheater" distribution - * (https://gitlab.com/mrjones.id.au/bluetoothheater) - * - * Copyright (C) 2018 Ray Jones - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -#include -#include "Icons.h" - -// 'Thermometer', 8x50px -const unsigned char bodyThermometerIcon [] PROGMEM = { - 0x00, 0x18, 0x24, 0x24, 0x24, 0x24, 0x24, 0x26, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, - 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x26, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, - 0x24, 0x24, 0x24, 0x24, 0x24, 0x26, 0x24, 0x24, 0x24, 0x24, 0x3c, 0x7e, 0xff, 0xff, 0xff, 0xff, - 0x7e, 0x3c -}; - -// 'ThermometerActual', 8x50px -const unsigned char ambientThermometerIcon [] PROGMEM = { - 0x00, 0x18, 0x24, 0x24, 0x24, 0x24, 0x24, 0x26, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, - 0x24, 0x26, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x26, 0x24, 0x24, 0x24, 0x24, - 0x24, 0x24, 0x24, 0x24, 0x24, 0x26, 0x24, 0x24, 0x24, 0x24, 0x3c, 0x7e, 0xff, 0xff, 0xff, 0xff, - 0x7e, 0x3c -}; - - -// 'ThermoPtr', 3x5px -const unsigned char thermoPtr [] PROGMEM = { - 0x80, 0xc0, 0xe0, 0xc0, 0x80 -}; - -// 'Bluetooth icon', 6x11px -const unsigned char BTicon [] PROGMEM = { - 0x20, 0x30, 0x28, 0xa4, 0x68, 0x30, 0x68, 0xa4, 0x28, 0x30, 0x20, -}; - -// 'wifiIcon', 13x10px -const unsigned char wifiIcon [] PROGMEM = { - 0x1f, 0xc0, 0x20, 0x20, 0x40, 0x10, 0x8f, 0x88, 0x10, 0x40, 0x20, 0x20, - 0x07, 0x00, 0x08, 0x80, 0x00, 0x00, 0x02, 0x00 -}; - -// 'wifiInIcon, 5x5px -const unsigned char wifiInIcon [] PROGMEM = { - 0x70, 0x70, 0xf8, 0x70, 0x20 -}; - -// 'wifiOutIcon, 5x5px -const unsigned char wifiOutIcon [] PROGMEM = { - 0x20, 0x70, 0xf8, 0x70, 0x70 -}; - -// 'BatteryIcon', 15x10px -const unsigned char BatteryIcon [] PROGMEM = { - 0x30, 0x18, 0xff, 0xfe, 0x80, 0x02, 0xb6, 0xda, 0xb6, 0xda, 0xb6, 0xda, 0xb6, 0xda, 0xb6, 0xda, - 0x80, 0x02, 0xff, 0xfe -}; - -// 'GlowPlugIcon', 16x9px -const unsigned char GlowPlugIcon [] PROGMEM = { - 0x71, 0xc7, 0x0e, 0x38, 0x14, 0x14, 0x12, 0x24, 0x11, 0x44, 0x11, 0x44, 0x11, 0x44, 0x0a, 0x28, - 0x0e, 0x38 -}; - -// 'HeatRise', 17x2px -const unsigned char GlowHeatIcon [] PROGMEM = { - 0x80, 0x00, 0x80, 0x40, 0x01, 0x00 -}; - -// 'Fan3_1a', 16x16px -const unsigned char FanIcon1 [] PROGMEM = { - 0x03, 0xc0, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x03, 0xc0, 0x07, 0xe0, 0x06, 0x60, - 0x7e, 0x7e, 0x87, 0xe1, 0x87, 0xe1, 0x84, 0x21, 0x84, 0x21, 0x78, 0x1e, 0x00, 0x00, 0x00, 0x00 -}; -// 'Fan3_2a', 16x16px -const unsigned char FanIcon2 [] PROGMEM = { - 0x00, 0x78, 0x00, 0x84, 0x00, 0x84, 0x00, 0x84, 0x00, 0x84, 0x7b, 0xf8, 0x87, 0xe0, 0x86, 0x60, - 0x86, 0x60, 0x87, 0xe0, 0x7b, 0xf8, 0x00, 0x84, 0x00, 0x84, 0x00, 0x84, 0x00, 0x84, 0x00, 0x78 -}; -// 'Fan3_3a', 16x16px -const unsigned char FanIcon3 [] PROGMEM = { - 0x00, 0x00, 0x00, 0x00, 0x78, 0x1e, 0x84, 0x21, 0x84, 0x21, 0x87, 0xe1, 0x87, 0xe1, 0x7e, 0x7e, - 0x06, 0x60, 0x07, 0xe0, 0x03, 0xc0, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x03, 0xc0 -}; -// 'Fan3_4a', 16x16px -const unsigned char FanIcon4 [] PROGMEM = { - 0x1e, 0x00, 0x21, 0x00, 0x21, 0x00, 0x21, 0x00, 0x21, 0x00, 0x1f, 0xde, 0x07, 0xe1, 0x06, 0x61, - 0x06, 0x61, 0x07, 0xe1, 0x1f, 0xde, 0x21, 0x00, 0x21, 0x00, 0x21, 0x00, 0x21, 0x00, 0x1e, 0x00 -}; - - -// 'FuelIcon', 7x12px -const unsigned char FuelIcon [] PROGMEM = { - 0x10, 0x10, 0x38, 0x38, 0x7c, 0x7c, 0xfe, 0xfe, 0xfe, 0xfe, 0x7c, 0x38 -}; - -// 'Target', 13x13px -const unsigned char TargetIcon [] PROGMEM = { - 0x0f, 0x80, 0x10, 0x40, 0x20, 0x20, 0x47, 0x10, 0x88, 0x88, 0x92, 0x48, 0x97, 0x48, 0x92, 0x48, - 0x88, 0x88, 0x47, 0x10, 0x20, 0x20, 0x10, 0x40, 0x0f, 0x80 -}; - -// 'repeat', 15x15px -const unsigned char repeatIcon [] PROGMEM = { - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x02, 0x00, 0x02, 0xf0, 0x04, 0xe0, 0x04, 0xe0, 0x08, 0x98, 0x30, 0x07, 0xc0 -}; - -// 'timerID1', 15x15px -const unsigned char timerID1Icon [] PROGMEM = { - 0x00, 0x00, 0x00, 0x00, 0x07, 0xc0, 0x09, 0x20, 0x11, 0x10, 0x21, 0x08, 0x2d, 0x08, 0x25, 0xe8, - 0x24, 0x08, 0x24, 0x08, 0x10, 0x10, 0x08, 0x20, 0x07, 0xc0, 0x00, 0x00, 0x00, 0x00 -}; - -// 'timerID2', 15x15px -const unsigned char timerID2Icon [] PROGMEM = { - 0x00, 0x00, 0x00, 0x00, 0x07, 0xc0, 0x09, 0x20, 0x11, 0x10, 0x21, 0x08, 0x2d, 0x08, 0x25, 0xe8, - 0x28, 0x08, 0x2c, 0x08, 0x10, 0x10, 0x08, 0x20, 0x07, 0xc0, 0x00, 0x00, 0x00, 0x00 -}; diff --git a/Arduino/BTCDieselHeater/src/fonts/Icons.h b/Arduino/BTCDieselHeater/src/fonts/Icons.h deleted file mode 100644 index b1c6d14..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/Icons.h +++ /dev/null @@ -1,95 +0,0 @@ -/* - * This file is part of the "bluetoothheater" distribution - * (https://gitlab.com/mrjones.id.au/bluetoothheater) - * - * Copyright (C) 2018 Ray Jones - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -// 'Thermometer', 8x50px -#define W_BULB_ICON 8 -#define H_BULB_ICON 50 -extern const unsigned char ambientThermometerIcon []; -extern const unsigned char bodyThermometerIcon []; - -// 'ThermoPtr', 3x5px -#define W_PTR_ICON 3 -#define H_PTR_ICON 5 -extern const unsigned char thermoPtr []; - -// 'Bluetooth icon', 6x11px -#define W_BT_ICON 6 -#define H_BT_ICON 11 -extern const unsigned char BTicon []; - -// 'wifiIcon', 13x10px -#define W_WIFI_ICON 13 -#define H_WIFI_ICON 10 -extern const unsigned char wifiIcon []; - -// 'wifiInIcon', 5x5px -#define W_WIFIIN_ICON 5 -#define H_WIFIIN_ICON 5 -extern const unsigned char wifiInIcon []; - -// 'wifiOutIcon', 5x5px -#define W_WIFIOUT_ICON 5 -#define H_WIFIOUT_ICON 5 -extern const unsigned char wifiOutIcon []; - -// 'BatteryIcon', 15x10px -#define W_BATT_ICON 15 -#define H_BATT_ICON 10 -extern const unsigned char BatteryIcon []; - -// 'GlowPlugIcon', 16x9px -#define W_GLOW_ICON 16 -#define H_GLOW_ICON 9 -extern const unsigned char GlowPlugIcon []; - -// 'HeatRise', 17x2px -#define W_HEAT_ICON 17 -#define H_HEAT_ICON 2 -extern const unsigned char GlowHeatIcon []; - -#define W_FAN_ICON 16 -#define H_FAN_ICON 16 -// 'Fan3_1a', 16x16px -extern const unsigned char FanIcon1 []; -// 'Fan3_2a', 16x16px -extern const unsigned char FanIcon2 []; -// 'Fan3_3a', 16x16px -extern const unsigned char FanIcon3 []; -// 'Fan3_4a', 16x16px -extern const unsigned char FanIcon4 []; - - -// 'FuelIcon', 7x12px -#define W_FUEL_ICON 7 -#define H_FUEL_ICON 12 -extern const unsigned char FuelIcon []; - -// 'Target', 13x13px -#define W_TARGET_ICON 13 -#define H_TARGET_ICON 13 -extern const unsigned char TargetIcon []; - -#define W_TIMER_ICON 15 -#define H_TIMER_ICON 15 -extern const unsigned char repeatIcon []; -extern const unsigned char timerID1Icon []; -extern const unsigned char timerID2Icon []; - diff --git a/Arduino/BTCDieselHeater/src/fonts/MiniFont.c b/Arduino/BTCDieselHeater/src/fonts/MiniFont.c deleted file mode 100644 index e35503a..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/MiniFont.c +++ /dev/null @@ -1,218 +0,0 @@ -/* - * This file is part of the "bluetoothheater" distribution - * (https://gitlab.com/mrjones.id.au/bluetoothheater) - * - * Copyright (C) 2018 Ray Jones - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -#include "MiniFont.h" -// -// Font data for a 3x5 font -// Hand carved by Ray Jones, based upon The Dot Factory font tool output structures -// - -// Character bitmaps for a 3x5 font -const uint8_t miniFontBitmaps[] PROGMEM = -{ - // @0 '.' (1 pixels wide) - 0x08, // # - - // @1 '0' (3 pixels wide) - 0x70, // ### - 0x88, // # # - 0x70, // ### - - // @4 '1' (3 pixels wide) - 0x48, // # # - 0xf8, // ##### - 0x08, // # - - // @7 '2' (3 pixels wide) - 0x98, // # ## - 0xa8, // # # # - 0x48, // # # - - // @10 '3' (3 pixels wide) - 0x88, // # # - 0xa8, // # # # - 0xf8, // ##### - - // @13 '4' (3 pixels wide) - 0xe0, // ### - 0x20, // # - 0xf8, // ##### - - // @16 '5' (3 pixels wide) - 0xe8, // ### # - 0xa8, // # # # - 0x90, // # # - - // @19 '6' (3 pixels wide) - 0x78, // #### - 0xa8, // # # # - 0xb8, // # ### - - // @22 '7' (3 pixels wide) - 0x80, // # - 0x80, // # - 0xf8, // ##### - - // @25 '8' (3 pixels wide) - 0xf8, // ##### - 0xa8, // # # # - 0xF8, // ##### - - // @28 '9' (3 pixels wide) - 0xe8, // ### # - 0xa8, // # # # - 0xF0, // #### - - // @31 '`' (2 pixels wide) - 0xC0, // ## - 0xC0, // ## - - // @33 'A' (3 pixels wide) - 0xf8, // ##### - 0xa0, // # # - 0xf8, // ##### - - // @36 'C' (3 pixels wide) - 0x70, // ### - 0x88, // # # - 0x88, // # # - - // @39 'H' (3 pixels wide) - 0xf8, // ##### - 0x20, // # - 0xf8, // ##### - - // @42 'P' (3 pixels wide) - 0xf8, // ##### - 0xa0, // # # - 0xe0, // ### - - // @45 'V' (3 pixels wide) - 0xf0, // #### - 0x08, // # - 0xf0, // #### - - // @48 'W' (3 pixels wide) - 0xf8, // ##### - 0x10, // # - 0xf8, // ##### - - // @51 'z' (3 pixels wide) - 0x28, // # # - 0x38, // ### - 0x28, // # # -}; - -// Character descriptors for a 3x5 font -// { [Char width in bits], [Char height in bits], [Offset into tahoma_16ptCharBitmaps in bytes] } -const FONT_CHAR_INFO miniFontDescriptors[] PROGMEM = -{ - {1, 5, 0}, // '.' - {0, 0, 0}, // '/' - {3, 5, 1}, // '0' - {3, 5, 4}, // '1' - {3, 5, 7}, // '2' - {3, 5, 10}, // '3' - {3, 5, 13}, // '4' - {3, 5, 16}, // '5' - {3, 5, 19}, // '6' - {3, 5, 22}, // '7' - {3, 5, 25}, // '8' - {3, 5, 28}, // '9' - {0, 0, 0}, // ':' - {0, 0, 0}, // ';' - {0, 0, 0}, // '<' - {0, 0, 0}, // '=' - {0, 0, 0}, // '>' - {0, 0, 0}, // '?' - {0, 0, 0}, // '@' - {3, 5, 33}, // 'A' - {0, 0, 0}, // 'B' - {3, 5, 36}, // 'C' - {0, 0, 0}, // 'D' - {0, 0, 0}, // 'E' - {0, 0, 0}, // 'F' - {0, 0, 0}, // 'G' - {3, 5, 39}, // 'H' - {0, 0, 0}, // 'I' - {0, 0, 0}, // 'J' - {0, 0, 0}, // 'K' - {0, 0, 0}, // 'L' - {0, 0, 0}, // 'M' - {0, 0, 0}, // 'N' - {0, 0, 0}, // 'O' - {3, 5, 42}, // 'P' - {0, 0, 0}, // 'Q' - {0, 0, 0}, // 'R' - {0, 0, 0}, // 'S' - {0, 0, 0}, // 'T' - {0, 0, 0}, // 'U' - {3, 5, 45}, // 'V' - {3, 5, 48}, // 'W' - {0, 0, 0}, // 'X' - {0, 0, 0}, // 'Y' - {0, 0, 0}, // 'Z' - {0, 0, 0}, // '[' - {0, 0, 0}, // '\' - {0, 0, 0}, // ']' - {0, 0, 0}, // '^' - {0, 0, 0}, // '_' - {2, 5, 31}, // '`' use for degree symbol - {0, 0, 0}, // 'a' - {0, 0, 0}, // 'b' - {0, 0, 0}, // 'c' - {0, 0, 0}, // 'd' - {0, 0, 0}, // 'e' - {0, 0, 0}, // 'f' - {0, 0, 0}, // 'g' - {0, 0, 0}, // 'h' - {0, 0, 0}, // 'i' - {0, 0, 0}, // 'j' - {0, 0, 0}, // 'k' - {0, 0, 0}, // 'l' - {0, 0, 0}, // 'm' - {0, 0, 0}, // 'n' - {0, 0, 0}, // 'o' - {0, 0, 0}, // 'p' - {0, 0, 0}, // 'q' - {0, 0, 0}, // 'r' - {0, 0, 0}, // 's' - {0, 0, 0}, // 't' - {0, 0, 0}, // 'u' - {0, 0, 0}, // 'v' - {0, 0, 0}, // 'w' - {0, 0, 0}, // 'x' - {0, 0, 0}, // 'y' - {3, 5, 51}, // 'z' -}; - -// Font information for Mini Font, a 3x5 font -// easier to leave in RAM, not that big anyway -const FONT_INFO miniFontInfo = -{ - 5, // Character height - '.', // Start character - 'z', // End character - 1, // Width, in pixels, of space character - miniFontDescriptors, // Character descriptor array - miniFontBitmaps, // Character bitmap array -}; - diff --git a/Arduino/BTCDieselHeater/src/fonts/MiniFont.h b/Arduino/BTCDieselHeater/src/fonts/MiniFont.h deleted file mode 100644 index 1a44d19..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/MiniFont.h +++ /dev/null @@ -1,27 +0,0 @@ -/* - * This file is part of the "bluetoothheater" distribution - * (https://gitlab.com/mrjones.id.au/bluetoothheater) - * - * Copyright (C) 2018 Ray Jones - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#include "FontTypes.h" - -// Font data for Mini Font, a 3x5 font -extern const uint8_t miniFontBitmaps[] PROGMEM; // stored in program flash memory -extern const FONT_CHAR_INFO miniFontDescriptors[] PROGMEM; // stored in program flash memory -extern const FONT_INFO miniFontInfo; - diff --git a/Arduino/BTCDieselHeater/src/fonts/OCRfont.cpp b/Arduino/BTCDieselHeater/src/fonts/OCRfont.cpp deleted file mode 100644 index f1762d3..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/OCRfont.cpp +++ /dev/null @@ -1,602 +0,0 @@ -#include "OCRfont.h" -// -// Font data for OCR A Extended 8pt -// -// Generated by The Dot Factory: -// http://www.eran.io/the-dot-factory-an-lcd-font-and-image-generator/ -// -///////////////////////////////////////////////////////////////////////////////////////////////////// -// -// Dot Factory Settings -// -// Flip/Rotate Padding Removal Line Wrap Descriptors -// [X] Flip X Height(Y): None (O) At column [X] Generate descriptor array -// [ ] Flip Y Width(X): Tightest ( ) At bitmap Char Width: In Bits -// 90deg Char Height: In Bits -// Font Height: In Bits -// Comments Byte [ ] Multiple descriptor arrays -// [X] Variable Name Bit layout: RowMajor -// [X] BMP visualise [#] Order: MSBfirst Create new when exceeds [80] -// [X] Char descriptor Format: Hex -// Style: Cpp Leading: 0x Image width: In Bits -// Image height: In Bits -// Variable name format -// Bitmaps: const uint8_t PROGMEM {0}Bitmaps Space char generation -// Char Info: const FONT_CHAR_INFO PROGMEM {0}Descriptors [X] Generate space bitmap -// Font Info: const FONT_INFO {0}FontInfo [2] pixels for space char -// Width: const uint8_t {0}Width -// Height: const uint8_t {0}Height -// -///////////////////////////////////////////////////////////////////////////////////////////////////// - -// Character bitmaps for OCR A Extended 8pt -const uint8_t oCRAExtended_8ptBitmaps[] PROGMEM = -{ - // @0 ' ' (2 pixels wide) - 0x00, 0x00, // - 0x00, 0x00, // - - // @4 ',' (3 pixels wide) - 0x80, // # - 0x80, // # - 0xE0, // ### - - // @7 '.' (1 pixels wide) - 0x80, // # - - // @8 '/' (5 pixels wide) - 0x02, // # - 0x0C, // ## - 0x10, // # - 0x60, // ## - 0x80, // # - - // @13 '0' (5 pixels wide) - 0xFE, // ####### - 0x82, // # # - 0x82, // # # - 0x82, // # # - 0xFE, // ####### - - // @18 '1' (5 pixels wide) - 0x82, // # # - 0x82, // # # - 0xFE, // ####### - 0x02, // # - 0x0E, // ### - - // @23 '2' (5 pixels wide) - 0x9E, // # #### - 0x92, // # # # - 0x92, // # # # - 0x92, // # # # - 0xF2, // #### # - - // @28 '3' (5 pixels wide) - 0x82, // # # - 0x92, // # # # - 0x92, // # # # - 0x92, // # # # - 0xEE, // ### ### - - // @33 '4' (4 pixels wide) - 0xF8, // ##### - 0x08, // # - 0x08, // # - 0x7E, // ###### - - // @37 '5' (5 pixels wide) - 0x02, // # - 0xF2, // #### # - 0x92, // # # # - 0x92, // # # # - 0x9E, // # #### - - // @42 '6' (5 pixels wide) - 0xFE, // ####### - 0x0A, // # # - 0x0A, // # # - 0x0A, // # # - 0x0E, // ### - - // @47 '7' (5 pixels wide) - 0x80, // # - 0x80, // # - 0x8E, // # ### - 0x90, // # # - 0xE0, // ### - - // @52 '8' (5 pixels wide) - 0x1E, // #### - 0xF2, // #### # - 0x92, // # # # - 0xF2, // #### # - 0x1E, // #### - - // @57 '9' (5 pixels wide) - 0xE0, // ### - 0xA0, // # # - 0xA0, // # # - 0xA0, // # # - 0xFE, // ####### - - // @62 ':' (1 pixels wide) - 0xA0, // # # - - // @63 'A' (5 pixels wide) - 0x06, // ## - 0x3C, // #### - 0xC4, // ## # - 0x3C, // #### - 0x06, // ## - - // @68 'B' (5 pixels wide) - 0xFE, // ####### - 0x92, // # # # - 0x92, // # # # - 0x92, // # # # - 0x6C, // ## ## - - // @73 'C' (5 pixels wide) - 0x38, // ### - 0x44, // # # - 0x82, // # # - 0x82, // # # - 0x82, // # # - - // @78 'D' (5 pixels wide) - 0x82, // # # - 0xFE, // ####### - 0x82, // # # - 0x44, // # # - 0x38, // ### - - // @83 'E' (5 pixels wide) - 0xFE, // ####### - 0x92, // # # # - 0x92, // # # # - 0x82, // # # - 0x82, // # # - - // @88 'F' (5 pixels wide) - 0xFE, // ####### - 0xA0, // # # - 0xA0, // # # - 0xA0, // # # - 0x80, // # - - // @93 'G' (5 pixels wide) - 0x3E, // ##### - 0x42, // # # - 0x8A, // # # # - 0x8A, // # # # - 0x8E, // # ### - - // @98 'H' (5 pixels wide) - 0xFE, // ####### - 0x10, // # - 0x10, // # - 0x10, // # - 0xFE, // ####### - - // @103 'I' (5 pixels wide) - 0x82, // # # - 0x82, // # # - 0xFE, // ####### - 0x82, // # # - 0x82, // # # - - // @108 'J' (4 pixels wide) - 0x0C, // ## - 0x02, // # - 0x02, // # - 0xFC, // ###### - - // @112 'K' (5 pixels wide) - 0xFE, // ####### - 0x10, // # - 0x28, // # # - 0x44, // # # - 0x82, // # # - - // @117 'L' (5 pixels wide) - 0xFE, // ####### - 0x02, // # - 0x02, // # - 0x02, // # - 0x02, // # - - // @122 'M' (5 pixels wide) - 0xFE, // ####### - 0xC0, // ## - 0x20, // # - 0xC0, // ## - 0xFE, // ####### - - // @127 'N' (5 pixels wide) - 0xFE, // ####### - 0x60, // ## - 0x10, // # - 0x0C, // ## - 0xFE, // ####### - - // @132 'O' (5 pixels wide) - 0x38, // ### - 0x44, // # # - 0x82, // # # - 0x44, // # # - 0x38, // ### - - // @137 'P' (5 pixels wide) - 0xFE, // ####### - 0x90, // # # - 0x90, // # # - 0x90, // # # - 0x60, // ## - - // @142 'Q' (5 pixels wide) - 0x3E, // ##### - 0x42, // # # - 0x4C, // # ## - 0x8E, // # ### - 0xFA, // ##### # - - // @147 'R' (5 pixels wide) - 0xFE, // ####### - 0xA0, // # # - 0xB0, // # ## - 0xAC, // # # ## - 0x42, // # # - - // @152 'S' (5 pixels wide) - 0x44, // # # - 0xA2, // # # # - 0x92, // # # # - 0x8A, // # # # - 0x46, // # ## - - // @157 'T' (5 pixels wide) - 0xC0, // ## - 0x80, // # - 0xFE, // ####### - 0x80, // # - 0xC0, // ## - - // @162 'U' (5 pixels wide) - 0xFC, // ###### - 0x02, // # - 0x02, // # - 0x02, // # - 0xFC, // ###### - - // @167 'V' (5 pixels wide) - 0xE0, // ### - 0x18, // ## - 0x06, // ## - 0x18, // ## - 0xE0, // ### - - // @172 'W' (5 pixels wide) - 0xFC, // ###### - 0x02, // # - 0x3C, // #### - 0x02, // # - 0xFC, // ###### - - // @177 'X' (5 pixels wide) - 0x82, // # # - 0x6C, // ## ## - 0x10, // # - 0x6C, // ## ## - 0x82, // # # - - // @182 'Y' (5 pixels wide) - 0xC0, // ## - 0x20, // # - 0x1E, // #### - 0x20, // # - 0xC0, // ## - - // @187 'Z' (5 pixels wide) - 0x82, // # # - 0x8E, // # ### - 0x92, // # # # - 0xE2, // ### # - 0x82, // # # - - // @192 '\' (5 pixels wide) - 0x80, // # - 0x60, // ## - 0x10, // # - 0x0C, // ## - 0x02, // # - - // @197 '`' (3 pixels wide) - 0x80, // # - 0x80, // # - 0x40, // # - - // @200 'a' (5 pixels wide) - 0x10, // # - 0xA8, // # # # - 0xA8, // # # # - 0xA8, // # # # - 0x78, // #### - - // @205 'b' (5 pixels wide) - 0xFE, // ####### - 0x14, // # # - 0x22, // # # - 0x22, // # # - 0x1C, // ### - - // @210 'c' (5 pixels wide) - 0x70, // ### - 0x88, // # # - 0x88, // # # - 0x88, // # # - 0x88, // # # - - // @215 'd' (5 pixels wide) - 0x1C, // ### - 0x22, // # # - 0x22, // # # - 0x14, // # # - 0xFE, // ####### - - // @220 'e' (5 pixels wide) - 0x70, // ### - 0xA8, // # # # - 0xA8, // # # # - 0xA8, // # # # - 0x68, // ## # - - // @225 'f' (4 pixels wide) - 0x20, // # - 0x7E, // ###### - 0xA0, // # # - 0x80, // # - - // @229 'g' (5 pixels wide) - 0x72, // ### # - 0x8A, // # # # - 0x8A, // # # # - 0x52, // # # # - 0xFC, // ###### - - // @234 'h' (5 pixels wide) - 0xFE, // ####### - 0x10, // # - 0x20, // # - 0x20, // # - 0x1E, // #### - - // @239 'i' (3 pixels wide) - 0x22, // # # - 0xBE, // # ##### - 0x02, // # - - // @242 'j' (4 pixels wide) - 0x01, 0x00, // # - 0x20, 0x80, // # # - 0x20, 0x80, // # # - 0xBF, 0x00, // # ###### - - // @250 'k' (5 pixels wide) - 0xFE, // ####### - 0x08, // # - 0x14, // # # - 0x14, // # # - 0x22, // # # - - // @255 'l' (3 pixels wide) - 0x82, // # # - 0xFE, // ####### - 0x02, // # - - // @258 'm' (5 pixels wide) - 0xF8, // ##### - 0x80, // # - 0x78, // #### - 0x80, // # - 0x78, // #### - - // @263 'n' (5 pixels wide) - 0xF8, // ##### - 0x40, // # - 0x80, // # - 0x80, // # - 0x78, // #### - - // @268 'o' (5 pixels wide) - 0x70, // ### - 0x88, // # # - 0x88, // # # - 0x88, // # # - 0x70, // ### - - // @273 'p' (5 pixels wide) - 0xFE, // ####### - 0x50, // # # - 0x88, // # # - 0x88, // # # - 0x70, // ### - - // @278 'q' (5 pixels wide) - 0x70, // ### - 0x88, // # # - 0x88, // # # - 0x50, // # # - 0xFE, // ####### - - // @283 'r' (5 pixels wide) - 0xF8, // ##### - 0x40, // # - 0x80, // # - 0x80, // # - 0x40, // # - - // @288 's' (5 pixels wide) - 0x48, // # # - 0xA8, // # # # - 0xA8, // # # # - 0xA8, // # # # - 0x90, // # # - - // @293 't' (5 pixels wide) - 0x20, // # - 0xFC, // ###### - 0x22, // # # - 0x22, // # # - 0x04, // # - - // @298 'u' (5 pixels wide) - 0xF0, // #### - 0x08, // # - 0x08, // # - 0x10, // # - 0xF8, // ##### - - // @303 'v' (5 pixels wide) - 0xC0, // ## - 0x30, // ## - 0x08, // # - 0x30, // ## - 0xC0, // ## - - // @308 'w' (5 pixels wide) - 0xF0, // #### - 0x08, // # - 0x70, // ### - 0x08, // # - 0xF0, // #### - - // @313 'x' (5 pixels wide) - 0x88, // # # - 0x50, // # # - 0x20, // # - 0x50, // # # - 0x88, // # # - - // @318 'y' (4 pixels wide) - 0xE2, // ### # - 0x1E, // #### - 0x18, // ## - 0xE0, // ### - - // @322 'z' (5 pixels wide) - 0x88, // # # - 0x98, // # ## - 0xA8, // # # # - 0xC8, // ## # - 0x88, // # # -}; - -// Character descriptors for OCR A Extended 8pt -// { [Char width in bits], [Offset into oCRAExtended_8ptCharBitmaps in bytes] } -const FONT_CHAR_INFO oCRAExtended_8ptDescriptors[] PROGMEM = -{ - {1, 7, 0}, // - {0, 0, 0}, // ! - {0, 0, 0}, // " - {0, 0, 0}, // # - {0, 0, 0}, // $ - {0, 0, 0}, // % - {0, 0, 0}, // & - {0, 0, 0}, // ' - {0, 0, 0}, // ( - {0, 0, 0}, // ) - {0, 0, 0}, // * - {0, 0, 0}, // + - {3, 3, 4}, // , - {0, 0, 0}, // - - {1, 1, 7}, // . - {5, 7, 8}, // / - {5, 7, 13}, // 0 - {5, 7, 18}, // 1 - {5, 7, 23}, // 2 - {5, 7, 28}, // 3 - {4, 7, 33}, // 4 - {5, 7, 37}, // 5 - {5, 7, 42}, // 6 - {5, 7, 47}, // 7 - {5, 7, 52}, // 8 - {5, 7, 57}, // 9 - {1, 3, 62}, // : - {0, 0, 0}, // ; - {0, 0, 0}, // < - {0, 0, 0}, // = - {0, 0, 0}, // > - {0, 0, 0}, // ? - {0, 0, 0}, // @ - {5, 7, 63}, // A - {5, 7, 68}, // B - {5, 7, 73}, // C - {5, 7, 78}, // D - {5, 7, 83}, // E - {5, 7, 88}, // F - {5, 7, 93}, // G - {5, 7, 98}, // H - {5, 7, 103}, // I - {4, 7, 108}, // J - {5, 7, 112}, // K - {5, 7, 117}, // L - {5, 7, 122}, // M - {5, 7, 127}, // N - {5, 7, 132}, // O - {5, 7, 137}, // P - {5, 7, 142}, // Q - {5, 7, 147}, // R - {5, 7, 152}, // S - {5, 7, 157}, // T - {5, 7, 162}, // U - {5, 7, 167}, // V - {5, 7, 172}, // W - {5, 7, 177}, // X - {5, 7, 182}, // Y - {5, 7, 187}, // Z - {0, 0, 0}, // [ - {5, 7, 192}, // \ . - {0, 0, 0}, // ] - {0, 0, 0}, // ^ - {0, 0, 0}, // _ - {3, 2, 197}, // ` - {5, 5, 200}, // a - {5, 7, 205}, // b - {5, 5, 210}, // c - {5, 7, 215}, // d - {5, 5, 220}, // e - {4, 7, 225}, // f - {5, 7, 229}, // g - {5, 7, 234}, // h - {3, 7, 239}, // i - {4, 9, 242}, // j - {5, 7, 250}, // k - {3, 7, 255}, // l - {5, 5, 258}, // m - {5, 5, 263}, // n - {5, 5, 268}, // o - {5, 7, 273}, // p - {5, 7, 278}, // q - {5, 5, 283}, // r - {5, 5, 288}, // s - {5, 7, 293}, // t - {5, 5, 298}, // u - {5, 5, 303}, // v - {5, 5, 308}, // w - {5, 5, 313}, // x - {4, 7, 318}, // y - {5, 5, 322}, // z -}; - -// Font information for OCR A Extended 8pt -const FONT_INFO oCRAExtended_8ptFontInfo = -{ - 12, // Character height - ' ', // Start character - 'z', // End character - 1, // Width, in pixels, of space character - oCRAExtended_8ptDescriptors, // Character descriptor array - oCRAExtended_8ptBitmaps, // Character bitmap array -}; - diff --git a/Arduino/BTCDieselHeater/src/fonts/OCRfont.h b/Arduino/BTCDieselHeater/src/fonts/OCRfont.h deleted file mode 100644 index 60432e7..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/OCRfont.h +++ /dev/null @@ -1,8 +0,0 @@ -#include "FontTypes.h" - -// Font data for OCR A Extended 8pt -extern const uint8_t PROGMEM oCRAExtended_8ptBitmaps []; -extern const FONT_INFO oCRAExtended_8ptFontInfo; -extern const FONT_CHAR_INFO PROGMEM oCRAExtended_8ptDescriptors[]; - - diff --git a/Arduino/BTCDieselHeater/src/fonts/Tahoma16.c b/Arduino/BTCDieselHeater/src/fonts/Tahoma16.c deleted file mode 100644 index 2ed0651..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/Tahoma16.c +++ /dev/null @@ -1,292 +0,0 @@ -// -// Font data for Tahoma 16pt -// -// Generated by The Dot Factory: -// http://www.eran.io/the-dot-factory-an-lcd-font-and-image-generator/ -// -///////////////////////////////////////////////////////////////////////////////////////////////////// -// -// Dot Factory Settings -// -// Flip/Rotate Padding Removal Line Wrap Descriptors -// [X] Flip X Height(Y): None (O) At column [X] Generate descriptor array -// [ ] Flip Y Width(X): Tightest ( ) At bitmap Char Width: In Bits -// 90deg Char Height: In Bits -// Font Height: In Bits -// Comments Byte [ ] Multiple descriptor arrays -// [X] Variable Name Bit layout: RowMajor -// [X] BMP visualise [#] Order: MSBfirst Create new when exceeds [80] -// [X] Char descriptor Format: Hex -// Style: Cpp Leading: 0x Image width: In Bits -// Image height: In Bits -// Variable name format -// Bitmaps: const uint8_t PROGMEM {0}Bitmaps Space char generation -// Char Info: const FONT_CHAR_INFO PROGMEM {0}Descriptors [ ] Generate space bitmap -// Font Info: const FONT_INFO {0}FontInfo [2] pixels for space char -// Width: const uint8_t {0}Width -// Height: const uint8_t {0}Height -// -///////////////////////////////////////////////////////////////////////////////////////////////////// - - -#include "tahoma16.h" - -// Character bitmaps for Tahoma 16pt -const uint8_t tahoma_16ptBitmaps[] PROGMEM = -{ - // @0 '.' (4 pixels wide) - 0x00, 0x0F, // #### - 0x00, 0x0F, // #### - 0x00, 0x0F, // #### - 0x00, 0x0F, // #### - - // @8 '0' (11 pixels wide) - 0x0F, 0xF0, // ######## - 0x3F, 0xFC, // ############ - 0x7F, 0xFE, // ############## - 0xFF, 0xFF, // ################ - 0xF0, 0x0F, // #### #### - 0xE0, 0x07, // ### ### - 0xF0, 0x0F, // #### #### - 0xFF, 0xFF, // ################ - 0x7F, 0xFE, // ############## - 0x3F, 0xFC, // ############ - 0x0F, 0xF0, // ######## - - // @30 '1' (10 pixels wide) - 0x38, 0x07, // ### ### - 0x38, 0x07, // ### ### - 0x38, 0x07, // ### ### - 0xFF, 0xFF, // ################ - 0xFF, 0xFF, // ################ - 0xFF, 0xFF, // ################ - 0xFF, 0xFF, // ################ - 0x00, 0x07, // ### - 0x00, 0x07, // ### - 0x00, 0x07, // ### - - // @50 '2' (11 pixels wide) - 0x70, 0x07, // ### ### - 0xE0, 0x0F, // ### #### - 0xE0, 0x1F, // ### ##### - 0xE0, 0x3F, // ### ###### - 0xE0, 0x7F, // ### ####### - 0xF1, 0xF7, // #### ##### ### - 0xFF, 0xE7, // ########### ### - 0x7F, 0xC7, // ######### ### - 0x7F, 0x87, // ######## ### - 0x3E, 0x07, // ##### ### - 0x00, 0x07, // ### - - // @72 '3' (11 pixels wide) - 0x70, 0x0E, // ### ### - 0xF0, 0x0F, // #### #### - 0xE0, 0x07, // ### ### - 0xE3, 0x87, // ### ### ### - 0xE3, 0x87, // ### ### ### - 0xE3, 0x87, // ### ### ### - 0xE7, 0xCF, // ### ##### #### - 0xFF, 0xFF, // ################ - 0x7E, 0xFE, // ###### ####### - 0x7E, 0xFE, // ###### ####### - 0x3C, 0x78, // #### #### - - // @94 '4' (12 pixels wide) - 0x00, 0xF0, // #### - 0x01, 0xF0, // ##### - 0x07, 0x70, // ### ### - 0x0E, 0x70, // ### ### - 0x38, 0x70, // ### ### - 0x70, 0x70, // ### ### - 0xFF, 0xFF, // ################ - 0xFF, 0xFF, // ################ - 0xFF, 0xFF, // ################ - 0xFF, 0xFF, // ################ - 0x00, 0x70, // ### - 0x00, 0x70, // ### - - // @118 '5' (11 pixels wide) - 0x00, 0x0E, // ### - 0xFF, 0x87, // ######### ### - 0xFF, 0x87, // ######### ### - 0xFF, 0x87, // ######### ### - 0xFF, 0x87, // ######### ### - 0xE3, 0x87, // ### ### ### - 0xE3, 0xCF, // ### #### #### - 0xE3, 0xFF, // ### ########## - 0xE3, 0xFE, // ### ######### - 0xE1, 0xFC, // ### ####### - 0xE0, 0xF8, // ### ##### - - // @140 '6' (11 pixels wide) - 0x07, 0xF0, // ####### - 0x1F, 0xFC, // ########### - 0x3F, 0xFE, // ############# - 0x7F, 0xFF, // ############### - 0xFB, 0x0F, // ##### ## #### - 0xF7, 0x07, // #### ### ### - 0xE7, 0x8F, // ### #### #### - 0xE7, 0xFF, // ### ########### - 0xE7, 0xFE, // ### ########## - 0xE3, 0xFC, // ### ######## - 0x01, 0xF8, // ###### - - // @162 '7' (11 pixels wide) - 0xE0, 0x01, // ### # - 0xE0, 0x07, // ### ### - 0xE0, 0x1F, // ### ##### - 0xE0, 0x7F, // ### ####### - 0xE1, 0xFF, // ### ######### - 0xE7, 0xFC, // ### ######### - 0xFF, 0xF0, // ############ - 0xFF, 0xC0, // ########## - 0xFF, 0x00, // ######## - 0xFC, 0x00, // ###### - 0xF0, 0x00, // #### - - // @184 '8' (11 pixels wide) - 0x3C, 0x3C, // #### #### - 0x7E, 0xFE, // ###### ####### - 0x7F, 0xFE, // ############## - 0xFF, 0xFF, // ################ - 0xE7, 0x8F, // ### #### #### - 0xE3, 0x87, // ### ### ### - 0xE3, 0xC7, // ### #### ### - 0xFF, 0xFF, // ################ - 0x7F, 0xFE, // ############## - 0x7E, 0xFE, // ###### ####### - 0x3C, 0x7C, // #### ##### - - // @206 '9' (11 pixels wide) - 0x1F, 0x80, // ###### - 0x3F, 0xC7, // ######## ### - 0x7F, 0xE7, // ########## ### - 0xFF, 0xE7, // ########### ### - 0xF1, 0xE7, // #### #### ### - 0xE0, 0xEF, // ### ### #### - 0xF0, 0xDF, // #### ## ##### - 0xFF, 0xFE, // ############### - 0x7F, 0xFC, // ############# - 0x3F, 0xF8, // ########### - 0x0F, 0xE0, // ####### - - // @228 '`' (8 pixels wide) - 0x3C, 0x00, // #### - 0x7E, 0x00, // ###### - 0xE7, 0x00, // ### ### - 0xC3, 0x00, // ## ## - 0xC3, 0x00, // ## ## - 0xE7, 0x00, // ### ### - 0x7E, 0x00, // ###### - 0x3C, 0x00, // #### - - // @244 'C' (12 pixels wide) - 0x07, 0xE0, // ###### - 0x1F, 0xF8, // ########## - 0x3F, 0xFC, // ############ - 0x7F, 0xFE, // ############## - 0xF8, 0x1F, // ##### ##### - 0xF0, 0x0F, // #### #### - 0xE0, 0x07, // ### ### - 0xE0, 0x07, // ### ### - 0xE0, 0x07, // ### ### - 0xE0, 0x07, // ### ### - 0x70, 0x0E, // ### ### - 0x78, 0x1E, // #### #### - - // @268 ':' (4 pixels wide) - 0x3C, 0x3C, // #### #### - 0x3C, 0x3C, // #### #### - 0x3C, 0x3C, // #### #### - 0x3C, 0x3C, // #### #### - - // @276 ' ' (4 pixels wide) - 0x00, 0x00, // - 0x00, 0x00, // - 0x00, 0x00, // - 0x00, 0x00, // - -}; - -// Character descriptors for Tahoma 16pt -// { [Char width in bits], [Char height in bits], [Offset into tahoma_16ptCharBitmaps in bytes] } -const FONT_CHAR_INFO tahoma_16ptDescriptors[] PROGMEM = -{ - {4, 16, 276}, // ' ' - {0, 0, 0}, // '!' - {0, 0, 0}, // '"' - {0, 0, 0}, // '#' - {0, 0, 0}, // '$' - {0, 0, 0}, // '%' - {0, 0, 0}, // '&' - {0, 0, 0}, // ''' - {0, 0, 0}, // '(' - {0, 0, 0}, // ')' - {0, 0, 0}, // '*' - {0, 0, 0}, // '+' - {0, 0, 0}, // , - {0, 0, 0}, // - - {4, 16, 0}, // '.' - {0, 0, 0}, // '/' - {11, 16, 8}, // '0' - {10, 16, 30}, // '1' - {11, 16, 50}, // '2' - {11, 16, 72}, // '3' - {12, 16, 94}, // '4' - {11, 16, 118}, // '5' - {11, 16, 140}, // '6' - {11, 16, 162}, // '7' - {11, 16, 184}, // '8' - {11, 16, 206}, // '9' - {4, 16, 268}, // ':' - {0, 0, 0}, // ';' - {0, 0, 0}, // '<' - {0, 0, 0}, // '=' - {0, 0, 0}, // '>' - {0, 0, 0}, // '?' - {0, 0, 0}, // '@' - {0, 0, 0}, // 'A' - {0, 0, 0}, // 'B' - {12, 16, 244}, // 'C' - {0, 0, 0}, // 'D' - {0, 0, 0}, // 'E' - {0, 0, 0}, // 'F' - {0, 0, 0}, // 'G' - {0, 0, 0}, // 'H' - {0, 0, 0}, // 'I' - {0, 0, 0}, // 'J' - {0, 0, 0}, // 'K' - {0, 0, 0}, // 'L' - {0, 0, 0}, // 'M' - {0, 0, 0}, // 'N' - {0, 0, 0}, // 'O' - {0, 0, 0}, // 'P' - {0, 0, 0}, // 'Q' - {0, 0, 0}, // 'R' - {0, 0, 0}, // 'S' - {0, 0, 0}, // 'T' - {0, 0, 0}, // 'U' - {0, 0, 0}, // 'V' - {0, 0, 0}, // 'W' - {0, 0, 0}, // 'X' - {0, 0, 0}, // 'Y' - {0, 0, 0}, // 'Z' - {0, 0, 0}, // '[' - {0, 0, 0}, // '\' - {0, 0, 0}, // ']' - {0, 0, 0}, // '^' - {0, 0, 0}, // '_' - {8, 16, 228}, // '`' use for degree symbol -}; - -// Font information for Tahoma 16pt -// easier to leave in RAM, not that big anyway -const FONT_INFO tahoma_16ptFontInfo = -{ - 16, // Character height - ' ', // Start character - '`', // End character - 2, // Width, in pixels, of space character - tahoma_16ptDescriptors, // Character descriptor array - tahoma_16ptBitmaps, // Character bitmap array -}; diff --git a/Arduino/BTCDieselHeater/src/fonts/Tahoma16.h b/Arduino/BTCDieselHeater/src/fonts/Tahoma16.h deleted file mode 100644 index e3a185a..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/Tahoma16.h +++ /dev/null @@ -1,7 +0,0 @@ -#include "FontTypes.h" - -// Font data for Tahoma 16pt -extern const uint8_t tahoma_16ptBitmaps[] PROGMEM; // stored in program flash memory -extern const FONT_CHAR_INFO tahoma_16ptDescriptors[] PROGMEM; // stored in program flash memory -extern const FONT_INFO tahoma_16ptFontInfo; - diff --git a/Arduino/BTCDieselHeater/src/fonts/Tahoma8.c b/Arduino/BTCDieselHeater/src/fonts/Tahoma8.c deleted file mode 100644 index 4c40020..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/Tahoma8.c +++ /dev/null @@ -1,784 +0,0 @@ -// -// Font data for Tahoma 8pt -// -// -// Generated by The Dot Factory: -// http://www.eran.io/the-dot-factory-an-lcd-font-and-image-generator/ -// -///////////////////////////////////////////////////////////////////////////////////////////////////// -// -// Dot Factory Settings -// -// Flip/Rotate Padding Removal Line Wrap Descriptors -// [X] Flip X Height(Y): None (O) At column [X] Generate descriptor array -// [ ] Flip Y Width(X): Tightest ( ) At bitmap Char Width: In Bits -// 90deg Char Height: In Bits -// Font Height: In Bits -// Comments Byte [ ] Multiple descriptor arrays -// [X] Variable Name Bit layout: RowMajor -// [X] BMP visualise [#] Order: MSBfirst Create new when exceeds [80] -// [X] Char descriptor Format: Hex -// Style: Cpp Leading: 0x Image width: In Bits -// Image height: In Bits -// Variable name format -// Bitmaps: const uint8_t PROGMEM {0}Bitmaps Space char generation -// Char Info: const FONT_CHAR_INFO PROGMEM {0}Descriptors [ ] Generate space bitmap -// Font Info: const FONT_INFO {0}FontInfo [2] pixels for space char -// Width: const uint8_t {0}Width -// Height: const uint8_t {0}Height -// -///////////////////////////////////////////////////////////////////////////////////////////////////// - - -#include "Tahoma8.h" - -// Character bitmaps for Tahoma 8pt -const uint8_t PROGMEM tahoma_8ptBitmaps [] = -{ - // @0 ' ' (2 pixels wide) - 0x00, 0x00, // - 0x00, 0x00, // - - // @4 '!' (1 pixels wide) - 0x1F, 0xA0, // ###### # - - // @6 '"' (3 pixels wide) - 0x38, 0x00, // ### - 0x00, 0x00, // - 0x38, 0x00, // ### - - // @12 '#' (7 pixels wide) - 0x00, 0x80, // # - 0x04, 0xE0, // # ### - 0x07, 0x80, // #### - 0x1C, 0xE0, // ### ### - 0x07, 0x80, // #### - 0x1C, 0x80, // ### # - 0x04, 0x00, // # - - // @26 '$' (5 pixels wide) - 0x06, 0x20, // ## # - 0x09, 0x20, // # # # - 0x3F, 0xF8, // ########### - 0x09, 0x20, // # # # - 0x08, 0xC0, // # ## - - // @36 '%' (10 pixels wide) - 0x0C, 0x00, // ## - 0x12, 0x00, // # # - 0x12, 0x00, // # # - 0x0C, 0x60, // ## ## - 0x01, 0x80, // ## - 0x06, 0x00, // ## - 0x18, 0xC0, // ## ## - 0x01, 0x20, // # # - 0x01, 0x20, // # # - 0x00, 0xC0, // ## - - // @56 '&' (7 pixels wide) - 0x0D, 0xC0, // ## ### - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x0D, 0x20, // ## # # - 0x00, 0xC0, // ## - 0x03, 0x40, // ## # - 0x00, 0x20, // # - - // @70 ''' (1 pixels wide) - 0x38, 0x00, // ### - - // @72 '(' (3 pixels wide) - 0x07, 0xC0, // ##### - 0x18, 0x30, // ## ## - 0x20, 0x08, // # # - - // @78 ')' (3 pixels wide) - 0x20, 0x08, // # # - 0x18, 0x30, // ## ## - 0x07, 0xC0, // ##### - - // @84 '*' (5 pixels wide) - 0x14, 0x00, // # # - 0x08, 0x00, // # - 0x3E, 0x00, // ##### - 0x08, 0x00, // # - 0x14, 0x00, // # # - - // @94 '+' (7 pixels wide) - 0x01, 0x00, // # - 0x01, 0x00, // # - 0x01, 0x00, // # - 0x0F, 0xE0, // ####### - 0x01, 0x00, // # - 0x01, 0x00, // # - 0x01, 0x00, // # - - // @108 ',' (2 pixels wide) - 0x00, 0x08, // # - 0x00, 0x70, // ### - - // @112 '-' (3 pixels wide) - 0x01, 0x00, // # - 0x01, 0x00, // # - 0x01, 0x00, // # - - // @118 '.' (1 pixels wide) - 0x00, 0x60, // ## - - // @120 '/' (3 pixels wide) - 0x00, 0x38, // ### - 0x07, 0xC0, // ##### - 0x38, 0x00, // ### - - // @126 '0' (5 pixels wide) - 0x0F, 0xC0, // ###### - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x0F, 0xC0, // ###### - - // @136 '1' (3 pixels wide) - 0x08, 0x20, // # # - 0x1F, 0xE0, // ######## - 0x00, 0x20, // # - - // @142 '2' (5 pixels wide) - 0x08, 0x60, // # ## - 0x10, 0xA0, // # # # - 0x11, 0x20, // # # # - 0x12, 0x20, // # # # - 0x0C, 0x20, // ## # - - // @152 '3' (5 pixels wide) - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x0D, 0xC0, // ## ### - - // @162 '4' (5 pixels wide) - 0x03, 0x00, // ## - 0x05, 0x00, // # # - 0x09, 0x00, // # # - 0x1F, 0xE0, // ######## - 0x01, 0x00, // # - - // @172 '5' (5 pixels wide) - 0x1E, 0x40, // #### # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x11, 0xC0, // # ### - - // @182 '6' (5 pixels wide) - 0x07, 0xC0, // ##### - 0x0A, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x01, 0xC0, // ### - - // @192 '7' (5 pixels wide) - 0x10, 0x00, // # - 0x10, 0x60, // # ## - 0x11, 0x80, // # ## - 0x16, 0x00, // # ## - 0x18, 0x00, // ## - - // @202 '8' (5 pixels wide) - 0x0D, 0xC0, // ## ### - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x0D, 0xC0, // ## ### - - // @212 '9' (5 pixels wide) - 0x0E, 0x00, // ### - 0x11, 0x20, // # # # - 0x11, 0x20, // # # # - 0x11, 0x40, // # # # - 0x0F, 0x80, // ##### - - // @222 ':' (1 pixels wide) - 0x06, 0x60, // ## ## - - // @224 ';' (2 pixels wide) - 0x00, 0x08, // # - 0x06, 0x70, // ## ### - - // @228 '<' (6 pixels wide) - 0x01, 0x00, // # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x04, 0x40, // # # - 0x04, 0x40, // # # - 0x08, 0x20, // # # - - // @240 '=' (7 pixels wide) - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - - // @254 '>' (6 pixels wide) - 0x08, 0x20, // # # - 0x04, 0x40, // # # - 0x04, 0x40, // # # - 0x02, 0x80, // # # - 0x02, 0x80, // # # - 0x01, 0x00, // # - - // @266 '?' (4 pixels wide) - 0x10, 0x00, // # - 0x11, 0xA0, // # ## # - 0x12, 0x00, // # # - 0x0C, 0x00, // ## - - // @274 '@' (9 pixels wide) - 0x07, 0xC0, // ##### - 0x08, 0x20, // # # - 0x13, 0x90, // # ### # - 0x14, 0x50, // # # # # - 0x14, 0x50, // # # # # - 0x17, 0xD0, // # ##### # - 0x10, 0x40, // # # - 0x08, 0x40, // # # - 0x07, 0x80, // #### - - // @292 'A' (6 pixels wide) - 0x00, 0xE0, // ### - 0x07, 0x80, // #### - 0x18, 0x80, // ## # - 0x18, 0x80, // ## # - 0x07, 0x80, // #### - 0x00, 0xE0, // ### - - // @304 'B' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x0D, 0xC0, // ## ### - - // @314 'C' (6 pixels wide) - 0x07, 0x80, // #### - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - - // @326 'D' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x08, 0x40, // # # - 0x07, 0x80, // #### - - // @338 'E' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x10, 0x20, // # # - - // @348 'F' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x12, 0x00, // # # - 0x12, 0x00, // # # - 0x12, 0x00, // # # - 0x12, 0x00, // # # - - // @358 'G' (6 pixels wide) - 0x07, 0x80, // #### - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x11, 0x20, // # # # - 0x11, 0x20, // # # # - 0x11, 0xE0, // # #### - - // @370 'H' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x1F, 0xE0, // ######## - - // @382 'I' (3 pixels wide) - 0x10, 0x20, // # # - 0x1F, 0xE0, // ######## - 0x10, 0x20, // # # - - // @388 'J' (4 pixels wide) - 0x00, 0x20, // # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x1F, 0xC0, // ####### - - // @396 'K' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x03, 0x00, // ## - 0x04, 0x80, // # # - 0x08, 0x40, // # # - 0x10, 0x20, // # # - - // @406 'L' (4 pixels wide) - 0x1F, 0xE0, // ######## - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - - // @414 'M' (7 pixels wide) - 0x1F, 0xE0, // ######## - 0x18, 0x00, // ## - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x06, 0x00, // ## - 0x18, 0x00, // ## - 0x1F, 0xE0, // ######## - - // @428 'N' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x18, 0x00, // ## - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x00, 0x60, // ## - 0x1F, 0xE0, // ######## - - // @440 'O' (7 pixels wide) - 0x07, 0x80, // #### - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x08, 0x40, // # # - 0x07, 0x80, // #### - - // @454 'P' (5 pixels wide) - 0x1F, 0xE0, // ######## - 0x11, 0x00, // # # - 0x11, 0x00, // # # - 0x11, 0x00, // # # - 0x0E, 0x00, // ### - - // @464 'Q' (7 pixels wide) - 0x07, 0x80, // #### - 0x08, 0x40, // # # - 0x10, 0x20, // # # - 0x10, 0x20, // # # - 0x10, 0x30, // # ## - 0x08, 0x48, // # # # - 0x07, 0x88, // #### # - - // @478 'R' (6 pixels wide) - 0x1F, 0xE0, // ######## - 0x11, 0x00, // # # - 0x11, 0x00, // # # - 0x11, 0x80, // # ## - 0x0E, 0x40, // ### # - 0x00, 0x20, // # - - // @490 'S' (5 pixels wide) - 0x0C, 0x20, // ## # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x12, 0x20, // # # # - 0x11, 0xC0, // # ### - - // @500 'T' (5 pixels wide) - 0x10, 0x00, // # - 0x10, 0x00, // # - 0x1F, 0xE0, // ######## - 0x10, 0x00, // # - 0x10, 0x00, // # - - // @510 'U' (6 pixels wide) - 0x1F, 0xC0, // ####### - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x1F, 0xC0, // ####### - - // @522 'V' (5 pixels wide) - 0x1C, 0x00, // ### - 0x03, 0x80, // ### - 0x00, 0x60, // ## - 0x03, 0x80, // ### - 0x1C, 0x00, // ### - - // @532 'W' (9 pixels wide) - 0x1C, 0x00, // ### - 0x03, 0x80, // ### - 0x00, 0x60, // ## - 0x03, 0x80, // ### - 0x1C, 0x00, // ### - 0x03, 0x80, // ### - 0x00, 0x60, // ## - 0x03, 0x80, // ### - 0x1C, 0x00, // ### - - // @550 'X' (5 pixels wide) - 0x18, 0x60, // ## ## - 0x04, 0x80, // # # - 0x03, 0x00, // ## - 0x04, 0x80, // # # - 0x18, 0x60, // ## ## - - // @560 'Y' (5 pixels wide) - 0x18, 0x00, // ## - 0x06, 0x00, // ## - 0x01, 0xE0, // #### - 0x06, 0x00, // ## - 0x18, 0x00, // ## - - // @570 'Z' (5 pixels wide) - 0x10, 0x60, // # ## - 0x10, 0xA0, // # # # - 0x13, 0x20, // # ## # - 0x14, 0x20, // # # # - 0x18, 0x20, // ## # - - // @580 '[' (3 pixels wide) - 0x3F, 0xF8, // ########### - 0x20, 0x08, // # # - 0x20, 0x08, // # # - - // @586 '\' (3 pixels wide) - 0x38, 0x00, // ### - 0x07, 0xC0, // ##### - 0x00, 0x38, // ### - - // @592 ']' (3 pixels wide) - 0x20, 0x08, // # # - 0x20, 0x08, // # # - 0x3F, 0xF8, // ########### - - // @598 '^' (7 pixels wide) - 0x02, 0x00, // # - 0x04, 0x00, // # - 0x08, 0x00, // # - 0x10, 0x00, // # - 0x08, 0x00, // # - 0x04, 0x00, // # - 0x02, 0x00, // # - - // @612 '_' (6 pixels wide) - 0x00, 0x08, // # - 0x00, 0x08, // # - 0x00, 0x08, // # - 0x00, 0x08, // # - 0x00, 0x08, // # - 0x00, 0x08, // # - - // @624 '`' (2 pixels wide) - 0x20, 0x00, // # - 0x10, 0x00, // # - - // @628 'a' (5 pixels wide) - 0x00, 0xC0, // ## - 0x05, 0x20, // # # # - 0x05, 0x20, // # # # - 0x05, 0x20, // # # # - 0x03, 0xE0, // ##### - - // @638 'b' (5 pixels wide) - 0x3F, 0xE0, // ######### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x03, 0xC0, // #### - - // @648 'c' (4 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - - // @656 'd' (5 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x3F, 0xE0, // ######### - - // @666 'e' (5 pixels wide) - 0x03, 0xC0, // #### - 0x05, 0x20, // # # # - 0x05, 0x20, // # # # - 0x05, 0x20, // # # # - 0x03, 0x40, // ## # - - // @676 'f' (3 pixels wide) - 0x1F, 0xE0, // ######## - 0x24, 0x00, // # # - 0x24, 0x00, // # # - - // @682 'g' (5 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x28, // # # # - 0x04, 0x28, // # # # - 0x04, 0x28, // # # # - 0x07, 0xF0, // ####### - - // @692 'h' (5 pixels wide) - 0x3F, 0xE0, // ######### - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x03, 0xE0, // ##### - - // @702 'i' (1 pixels wide) - 0x17, 0xE0, // # ###### - - // @704 'j' (2 pixels wide) - 0x04, 0x08, // # # - 0x17, 0xF0, // # ####### - - // @708 'k' (5 pixels wide) - 0x3F, 0xE0, // ######### - 0x01, 0x00, // # - 0x02, 0x80, // # # - 0x04, 0x40, // # # - 0x00, 0x20, // # - - // @718 'l' (1 pixels wide) - 0x3F, 0xE0, // ######### - - // @720 'm' (7 pixels wide) - 0x07, 0xE0, // ###### - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x03, 0xE0, // ##### - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x03, 0xE0, // ##### - - // @734 'n' (5 pixels wide) - 0x07, 0xE0, // ###### - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x04, 0x00, // # - 0x03, 0xE0, // ##### - - // @744 'o' (5 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x03, 0xC0, // #### - - // @754 'p' (5 pixels wide) - 0x07, 0xF8, // ######## - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x03, 0xC0, // #### - - // @764 'q' (5 pixels wide) - 0x03, 0xC0, // #### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x04, 0x20, // # # - 0x07, 0xF8, // ######## - - // @774 'r' (3 pixels wide) - 0x07, 0xE0, // ###### - 0x02, 0x00, // # - 0x04, 0x00, // # - - // @780 's' (4 pixels wide) - 0x03, 0x20, // ## # - 0x05, 0x20, // # # # - 0x04, 0xA0, // # # # - 0x04, 0xC0, // # ## - - // @788 't' (3 pixels wide) - 0x1F, 0xC0, // ####### - 0x04, 0x20, // # # - 0x04, 0x20, // # # - - // @794 'u' (5 pixels wide) - 0x07, 0xC0, // ##### - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x00, 0x20, // # - 0x07, 0xE0, // ###### - - // @804 'v' (5 pixels wide) - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x00, 0x60, // ## - 0x01, 0x80, // ## - 0x06, 0x00, // ## - - // @814 'w' (7 pixels wide) - 0x07, 0x80, // #### - 0x00, 0x60, // ## - 0x01, 0x80, // ## - 0x06, 0x00, // ## - 0x01, 0x80, // ## - 0x00, 0x60, // ## - 0x07, 0x80, // #### - - // @828 'x' (5 pixels wide) - 0x04, 0x20, // # # - 0x02, 0x40, // # # - 0x01, 0x80, // ## - 0x02, 0x40, // # # - 0x04, 0x20, // # # - - // @838 'y' (5 pixels wide) - 0x06, 0x00, // ## - 0x01, 0x98, // ## ## - 0x00, 0x60, // ## - 0x01, 0x80, // ## - 0x06, 0x00, // ## - - // @848 'z' (4 pixels wide) - 0x04, 0x60, // # ## - 0x04, 0xA0, // # # # - 0x05, 0x20, // # # # - 0x06, 0x20, // ## # - - // @856 '{' (4 pixels wide) - 0x01, 0x00, // # - 0x01, 0x00, // # - 0x1E, 0xF0, // #### #### - 0x20, 0x08, // # # - - // @864 '|' (1 pixels wide) - 0x3F, 0xF8, // ########### - - // @866 '}' (4 pixels wide) - 0x20, 0x08, // # # - 0x1E, 0xF0, // #### #### - 0x01, 0x00, // # - 0x01, 0x00, // # - - // @874 '~' (7 pixels wide) - 0x01, 0x80, // ## - 0x02, 0x00, // # - 0x02, 0x00, // # - 0x01, 0x00, // # - 0x00, 0x80, // # - 0x00, 0x80, // # - 0x03, 0x00, // ## -}; - -// Character descriptors for Tahoma 8pt -// { [Char width in bits], [Char height in bits], [Offset into tahoma_8ptCharBitmaps in bytes] } -const FONT_CHAR_INFO PROGMEM tahoma_8ptDescriptors[] = -{ - {2, 13, 0}, // - {1, 13, 4}, // ! - {3, 13, 6}, // " - {7, 13, 12}, // # - {5, 13, 26}, // $ - {10, 13, 36}, // % - {7, 13, 56}, // & - {1, 13, 70}, // ' - {3, 13, 72}, // ( - {3, 13, 78}, // ) - {5, 13, 84}, // * - {7, 13, 94}, // + - {2, 13, 108}, // , - {3, 13, 112}, // - - {1, 13, 118}, // . - {3, 13, 120}, // / - {5, 13, 126}, // 0 - {3, 13, 136}, // 1 - {5, 13, 142}, // 2 - {5, 13, 152}, // 3 - {5, 13, 162}, // 4 - {5, 13, 172}, // 5 - {5, 13, 182}, // 6 - {5, 13, 192}, // 7 - {5, 13, 202}, // 8 - {5, 13, 212}, // 9 - {1, 13, 222}, // : - {2, 13, 224}, // ; - {6, 13, 228}, // < - {7, 13, 240}, // = - {6, 13, 254}, // > - {4, 13, 266}, // ? - {9, 13, 274}, // @ - {6, 13, 292}, // A - {5, 13, 304}, // B - {6, 13, 314}, // C - {6, 13, 326}, // D - {5, 13, 338}, // E - {5, 13, 348}, // F - {6, 13, 358}, // G - {6, 13, 370}, // H - {3, 13, 382}, // I - {4, 13, 388}, // J - {5, 13, 396}, // K - {4, 13, 406}, // L - {7, 13, 414}, // M - {6, 13, 428}, // N - {7, 13, 440}, // O - {5, 13, 454}, // P - {7, 13, 464}, // Q - {6, 13, 478}, // R - {5, 13, 490}, // S - {5, 13, 500}, // T - {6, 13, 510}, // U - {5, 13, 522}, // V - {9, 13, 532}, // W - {5, 13, 550}, // X - {5, 13, 560}, // Y - {5, 13, 570}, // Z - {3, 13, 580}, // [ - {3, 13, 586}, // \ . - {3, 13, 592}, // ] - {7, 13, 598}, // ^ - {6, 13, 612}, // _ - {2, 13, 624}, // ` - {5, 13, 628}, // a - {5, 13, 638}, // b - {4, 13, 648}, // c - {5, 13, 656}, // d - {5, 13, 666}, // e - {3, 13, 676}, // f - {5, 13, 682}, // g - {5, 13, 692}, // h - {1, 13, 702}, // i - {2, 13, 704}, // j - {5, 13, 708}, // k - {1, 13, 718}, // l - {7, 13, 720}, // m - {5, 13, 734}, // n - {5, 13, 744}, // o - {5, 13, 754}, // p - {5, 13, 764}, // q - {3, 13, 774}, // r - {4, 13, 780}, // s - {3, 13, 788}, // t - {5, 13, 794}, // u - {5, 13, 804}, // v - {7, 13, 814}, // w - {5, 13, 828}, // x - {5, 13, 838}, // y - {4, 13, 848}, // z - {4, 13, 856}, // { - {1, 13, 864}, // | - {4, 13, 866}, // } - {7, 13, 874}, // ~ -}; - -// Font information for Tahoma 8pt -const FONT_INFO tahoma_8ptFontInfo = -{ - 13, // Character height - ' ', // Start character - '~', // End character - 2, // Width, in pixels, of space character - tahoma_8ptDescriptors, // Character descriptor array - tahoma_8ptBitmaps, // Character bitmap array -}; - diff --git a/Arduino/BTCDieselHeater/src/fonts/Tahoma8.h b/Arduino/BTCDieselHeater/src/fonts/Tahoma8.h deleted file mode 100644 index 2dbf400..0000000 --- a/Arduino/BTCDieselHeater/src/fonts/Tahoma8.h +++ /dev/null @@ -1,7 +0,0 @@ -#include "FontTypes.h" - -// Font data for Tahoma 8pt -extern const uint8_t tahoma_8ptBitmaps[] PROGMEM; -extern const FONT_CHAR_INFO tahoma_8ptDescriptors[] PROGMEM; -extern const FONT_INFO tahoma_8ptFontInfo; -