Compare commits
27 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
551853360c | ||
|
|
711a3e9182 | ||
|
|
7e1e81cc6f | ||
|
|
a01cb7a4be | ||
|
|
cb5d4bc49d | ||
|
|
67e3c44f54 | ||
|
|
e47753d5ab | ||
|
|
07d9b15ecc | ||
|
|
1522c419cf | ||
|
|
ddedd9ad4f | ||
|
|
0f3bb4c356 | ||
|
|
0ebaab5847 | ||
|
|
203a7c154b | ||
|
|
ebfe457f65 | ||
|
|
8c73aa0de4 | ||
|
|
53a1b9b7f4 | ||
|
|
c9d0d5bdb3 | ||
|
|
4f9e738501 | ||
|
|
fcaf909a54 | ||
|
|
9b51750a1d | ||
|
|
fceb81287e | ||
|
|
c3d8d246dc | ||
|
|
1f7cdf9694 | ||
|
|
b2db129ab8 | ||
|
|
b7e4249d2e | ||
|
|
0bbdda5b55 | ||
|
|
acb97f1d46 |
90
README.md
90
README.md
@@ -1,27 +1,27 @@
|
||||
# TS100
|
||||
This is a complete open source re-write of the software for the ts100 soldering iron.
|
||||
This is a complete re-write of the open source software for the ts100 soldering iron.
|
||||
This project is feature complete for use as a soldering iron, but is still open to ideas and suggestions.
|
||||
|
||||
This was started to remove the need for USB for changing system settings.
|
||||
This project was started to remove the need for USB for changing system settings.
|
||||
In the latest official firmware they have also added a settings menu system, so it is still worth comparing the two firmwares to select your preferred option.
|
||||
|
||||
The software has similar functionality to the original firmware.
|
||||
|
||||
## Features Working
|
||||
## Features
|
||||
* Soldering / Temperature control
|
||||
* Full PID Iron Temp
|
||||
* Adjusting temperature
|
||||
* Automatic sleep
|
||||
* Full PID iron temperature control
|
||||
* Automatic sleep with selectable sensitivity
|
||||
* Motion wake support
|
||||
* Basic settings menu
|
||||
* Input voltage UVLO measurement
|
||||
* Saving settings to flash for persistence
|
||||
* Improved GUI
|
||||
* Use hardware I2C for communications
|
||||
* Settings menu
|
||||
* Input voltage UVLO measurement for battery powered use
|
||||
* All settings saved
|
||||
* Improved readability Fonts
|
||||
* Use hardware features to improve reliability
|
||||
* Can disable movement detection if desired
|
||||
## Features still to be implemented
|
||||
* Manual Temp Calibration
|
||||
* Calibration of the temperature offset
|
||||
|
||||
# Upgrading your ts100 iron
|
||||
This is completely safe, if it goes wrong just put the .hex file from the official website onto the unit and your back to the old firmware :)
|
||||
This is completely safe, if it goes wrong just put the .hex file from the official website onto the unit and your back to the old firmware. Downloads for the hex files to flash are available on the [releases page.](https://github.com/Ralim/ts100/releases)
|
||||
**You will need a windows computer (7,8,10 tested), using the normal windows explorer to load the firmware.
|
||||
The bootloader does not appear to work under mac or linux at the moment.**
|
||||
|
||||
1. Hold the button closest to the tip, and plug in the USB to the computer.
|
||||
2. The unit will appear as a USB drive.
|
||||
@@ -29,4 +29,60 @@ This is completely safe, if it goes wrong just put the .hex file from the offici
|
||||
4. The unit will disconnect and reconnect.
|
||||
5. The filename will have changed to end in .RDY or .ERR .
|
||||
6. If it ends with .RDY your done! Otherwise something went wrong.
|
||||
7. If it went wrong try on a windows computer, some Mac / Linux machines do not play well with their boot loader.
|
||||
7. Disconnect the USB and power up the iron. You're good to go.
|
||||
|
||||
For the more adventurerous out there, you can also load this firmware onto the device using a SWD programmer.
|
||||
On the bottom of the MCU riser pcb, there are 4 pads for programming.
|
||||
There is a complete device flash backup included in this repository. (Note this includes the bootloader, so will need a SWD programmer to load onto the unit). Please do not use the backup of the bootloader for anything malicious, its only saved here for those who are tinkering with their iron and decide to replace it.
|
||||
|
||||
# New Menu System
|
||||
This new firmware uses a new menu system to allow access to the settings on the device.
|
||||
When on the main screen, the unit shows prompts for the two most common operations.
|
||||
-> Pressing the button near the tip enters soldering mode
|
||||
-> Pressing the button near the power input enters the settings menu.
|
||||
-> Pressing both buttons together enters the Extras menu
|
||||
## Soldering mode
|
||||
In this mode the iron works as you would expect, pressing either button will take you to a temperature change screen. Use each button to go up and down in temperature. Pressing both buttons will exit you from the temperature menu (or wait 3 seconds and it will time out).
|
||||
Pressing both buttons will also exit the soldering mode.
|
||||
|
||||
## Settings Menu
|
||||
This menu allows you to cycle through all the options and set their values.
|
||||
The button near the tip cycles through the options, and the one near the usb changes the selected option.
|
||||
Note that settings are not saved until you exit the menu, and some settings such as screen flip do not apply until a power cycle is applied.
|
||||
|
||||
* UVCO -> Undervoltage cut out level, settable in 1V increments from 10-24V
|
||||
* SLTME -> Sleep time, how long it takes before the unit goes to sleep
|
||||
* STMP -> The temperature the unit drops to in sleep mode
|
||||
* SHTME -> Shutdown Time, how long the unit will wait after movement before shutting down completely
|
||||
* MOTION -> Wether motion detection is enabled or not
|
||||
* TMPUNIT -> Temperature unit, C or F
|
||||
* FLPDSP -> Flip display for left handed users
|
||||
* SENSE -> Motion Sensitivity, H is more sensitive. L is lowest sensitivity (ie takes more movement to trigger)
|
||||
|
||||
## Extras Menu
|
||||
This menu defaults to showing the current temperature on the tip.
|
||||
Pressing the button near the iron tip will show the current input voltage. Pressing the other button while this is show will allow you to calibrate the reading if your iron is like mine and is not overly accurate out of the factory. (Press buttons to change measurement up and down, press both to exit and save).
|
||||
|
||||
Pressing the button near the usb enters the temperature offset setting menu, when the iron is cold, pressing the other button will start the unit calibrating for any offset in the tip temperature.
|
||||
|
||||
# Version Changes:
|
||||
V1.06
|
||||
- Changes H and C when the iron is heating to the minidso chevron like images
|
||||
|
||||
V1.05
|
||||
- Adds ability to calibrate the input voltage measurement
|
||||
|
||||
V1.04
|
||||
- Increased accuracy of the temperature control
|
||||
- Improved PID response slightly
|
||||
- Allows temperature offset calibration
|
||||
- Nicer idle screen
|
||||
|
||||
V1.03
|
||||
- Improved Button handling
|
||||
- Ability to set motion sensitivity
|
||||
- DC voltmeter page shows input voltage
|
||||
|
||||
V1.02
|
||||
- Adds hold both buttons on IDLE to access the therometer mode.
|
||||
- Changes the exit soldering mode to be holding both buttons (Like original firmware).
|
||||
|
||||
@@ -1,21 +0,0 @@
|
||||
# System Design
|
||||
|
||||
# Movement Detection
|
||||
The unit has a MMA8652FC Accelerometer on the small sub board along with the STM32.
|
||||
This is used for motion detection of the soldering iron.
|
||||
|
||||
# USB Disk
|
||||
When the unit is plugged into the computer, it presents a FAT device to the operating system over the usb connection.
|
||||
This is implemented using a ram buffer for the disk.
|
||||
|
||||
|
||||
|
||||
|
||||
# Future improvements to be made
|
||||
These features are things I would like to add to the firmware
|
||||
|
||||
* Use the sysTick hardware for timing of events
|
||||
* Move all the settings to an on device menu system instead of usb link
|
||||
* Move error codes into a unified struct
|
||||
* Rewrite most of the OLED stack to not require hardcoded values
|
||||
* Rework the modes of the unit to be neater
|
||||
BIN
TS100 V2.46 Schematics V1.0.pdf
Normal file
BIN
TS100 V2.46 Schematics V1.0.pdf
Normal file
Binary file not shown.
25
VERSION.txt
25
VERSION.txt
@@ -1,25 +0,0 @@
|
||||
v2.11 update (2015/08/03)
|
||||
1, optimizing the key for delay;
|
||||
2, optimized display processing
|
||||
3, optimization of high-temperature alarm;
|
||||
4, to increase the maximum voltage alarm;
|
||||
5, the newly added screen protection, enter standby interface for some time, the screen will shut itself down, or move the iron screen button will automatically light up;
|
||||
6, optimizing the movement decision
|
||||
|
||||
v2.10 update (2015/07/14)
|
||||
1, temperature calibration is not refresh bug;
|
||||
2, Cancel USB-powered thermometer into the function;
|
||||
|
||||
---Original --
|
||||
v2.11 <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>(20150803)
|
||||
1<EFBFBD><EFBFBD> <09>Ż<EFBFBD><C5BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
2<EFBFBD><EFBFBD> <09>Ż<EFBFBD><C5BB><EFBFBD>ʾ<EFBFBD><CABE><EFBFBD><EFBFBD>
|
||||
3<EFBFBD><EFBFBD> <09>Ż<EFBFBD><C5BB><EFBFBD><EFBFBD>±<EFBFBD><C2B1><EFBFBD><EFBFBD><EFBFBD>
|
||||
4<EFBFBD><EFBFBD> <09><><EFBFBD>߱<EFBFBD><DFB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ߵ<EFBFBD>ѹ<EFBFBD><D1B9>
|
||||
5<EFBFBD><EFBFBD> <09>¼<EFBFBD><C2BC><EFBFBD><EFBFBD><EFBFBD>Ļ<EFBFBD><C4BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ܣ<EFBFBD><DCA3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>һ<EFBFBD><D2BB>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ļ<EFBFBD><C4BB><EFBFBD>Լ<EFBFBD><D4BC>رգ<D8B1><D5A3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ƶ<EFBFBD><C6B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ļ<EFBFBD><C4BB><EFBFBD>Զ<EFBFBD><D4B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
6<EFBFBD><EFBFBD> <09>Ż<EFBFBD><C5BB>ƶ<EFBFBD><C6B6>ж<EFBFBD>
|
||||
|
||||
v2.10 <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>(20150714)
|
||||
1<EFBFBD><EFBFBD> <09>¶<EFBFBD>Уʱû<CAB1><C3BB>ˢ<EFBFBD>µ<EFBFBD>bug<75><67>
|
||||
2<EFBFBD><EFBFBD> ȡ<><C8A1>USB<53><42><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD>¶ȼƵĹ<C6B5><C4B9>ܣ<EFBFBD>
|
||||
|
||||
@@ -103,7 +103,7 @@
|
||||
</extensions>
|
||||
</storageModule>
|
||||
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||
<configuration artifactExtension="elf" artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="fr.ac6.managedbuild.config.gnu.cross.exe.release.1113492345" name="Release" parent="fr.ac6.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary and Printing size information:" postbuildStep="arm-none-eabi-objcopy -O binary "${BuildArtifactFileBaseName}.elf" "${BuildArtifactFileBaseName}.bin"; arm-none-eabi-size -B "${BuildArtifactFileName}"">
|
||||
<configuration artifactExtension="elf" artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="fr.ac6.managedbuild.config.gnu.cross.exe.release.1113492345" name="Release" parent="fr.ac6.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary and Printing size information:" postbuildStep="arm-none-eabi-objcopy -O binary "${BuildArtifactFileBaseName}.elf" "${BuildArtifactFileBaseName}.bin"; arm-none-eabi-size -B "${BuildArtifactFileName}";arm-none-eabi-objcopy -O ihex "${BuildArtifactFileBaseName}.elf" "${BuildArtifactFileBaseName}.hex"">
|
||||
<folderInfo id="fr.ac6.managedbuild.config.gnu.cross.exe.release.1113492345." name="/" resourcePath="">
|
||||
<toolChain id="fr.ac6.managedbuild.toolchain.gnu.cross.exe.release.668479481" name="Ac6 STM32 MCU GCC" superClass="fr.ac6.managedbuild.toolchain.gnu.cross.exe.release">
|
||||
<option id="fr.ac6.managedbuild.option.gnu.cross.mcu.302274410" name="Mcu" superClass="fr.ac6.managedbuild.option.gnu.cross.mcu" value="STM32F103T8Ux" valueType="string"/>
|
||||
|
||||
1
workspace/ts100/.gitignore
vendored
1
workspace/ts100/.gitignore
vendored
@@ -1 +1,2 @@
|
||||
/Debug/
|
||||
/Release/
|
||||
|
||||
@@ -15,6 +15,6 @@
|
||||
extern volatile uint16_t ADC1ConvertedValue[2];
|
||||
|
||||
uint16_t Get_ADC1Value(uint8_t i);
|
||||
uint16_t readIronTemp(uint16_t calibration,uint8_t read);//read the iron temp in C X10
|
||||
uint16_t readDCVoltage();/*Get the system voltage X10*/
|
||||
uint16_t readIronTemp(uint16_t calibration_temp, uint8_t read,uint16_t setPointTemp); //read the iron temp in C X10
|
||||
uint16_t readDCVoltage(uint16_t divFactor);/*Get the system voltage X10*/
|
||||
#endif /* ANALOG_H_ */
|
||||
|
||||
@@ -10,86 +10,183 @@
|
||||
#ifndef FONT_H_
|
||||
#define FONT_H_
|
||||
|
||||
const u8 FONT[]={
|
||||
0x00,0xF0,0xFC,0x0E,0x82,0xC2,0x62,0x1E,0xFC,0xF0,0x00,0x00,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x1F,0x11,0x10,0x10,0x1C,0x0F,0x03,0x00,0x00,0x00,0x00,/*0*/
|
||||
0x00,0x08,0x04,0x02,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x10,0x10,0x1F,0x1F,0x10,0x10,0x10,0x00,0x00,0x00,0x00,0x00,/*1*/
|
||||
0x00,0x04,0x02,0x02,0x02,0xC6,0xFC,0x78,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x18,0x1C,0x16,0x13,0x11,0x10,0x10,0x10,0x00,0x00,0x00,0x00,0x00,/*2*/
|
||||
0x00,0x02,0x02,0x42,0x42,0x66,0xFE,0x9C,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x10,0x10,0x10,0x10,0x08,0x0F,0x07,0x00,0x00,0x00,0x00,0x00,/*3*/
|
||||
0x00,0x00,0x80,0xE0,0x30,0x1C,0x06,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x03,0x03,0x02,0x02,0x02,0x02,0x1F,0x1F,0x02,0x02,0x00,0x00,0x00,/*4*/
|
||||
0x00,0x7E,0x7E,0x42,0x42,0x42,0xC2,0x82,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x10,0x10,0x10,0x10,0x08,0x0F,0x07,0x00,0x00,0x00,0x00,0x00,/*5*/
|
||||
0x00,0xE0,0xF8,0x8C,0x44,0x42,0x42,0xC2,0x82,0x80,0x00,0x00,0x00,0x00,
|
||||
0x00,0x07,0x0F,0x18,0x10,0x10,0x10,0x18,0x0F,0x07,0x00,0x00,0x00,0x00,/*6*/
|
||||
0x00,0x02,0x02,0x02,0x02,0xC2,0xF2,0x1E,0x06,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x10,0x1C,0x0F,0x03,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*7*/
|
||||
0x00,0x38,0x7C,0x66,0xC2,0x82,0xC2,0x66,0x7C,0x3C,0x00,0x00,0x00,0x00,
|
||||
0x00,0x0E,0x0F,0x19,0x10,0x10,0x10,0x19,0x0F,0x0E,0x00,0x00,0x00,0x00,/*8*/
|
||||
0x00,0x78,0x7C,0xC6,0x82,0x82,0x82,0x46,0xFC,0xF8,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x10,0x10,0x10,0x10,0x08,0x0C,0x07,0x03,0x00,0x00,0x00,0x00,/*9*/
|
||||
0x00,0x00,0x80,0xF0,0x1E,0x02,0x1E,0xF0,0x80,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1C,0x0F,0x03,0x02,0x02,0x02,0x03,0x0F,0x1C,0x00,0x00,0x00,0x00,/*A*/
|
||||
0x00,0xFE,0xFE,0x42,0x42,0x42,0xE6,0xBE,0x9C,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x10,0x10,0x10,0x18,0x0F,0x07,0x00,0x00,0x00,0x00,0x00,/*B*/
|
||||
0x00,0xF0,0xF8,0x0C,0x06,0x02,0x02,0x02,0x04,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x0C,0x18,0x10,0x10,0x10,0x08,0x00,0x00,0x00,0x00,0x00,/*C*/
|
||||
0x00,0xFE,0xFE,0x02,0x02,0x02,0x06,0x0C,0xFC,0xF0,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x10,0x10,0x10,0x18,0x0C,0x07,0x03,0x00,0x00,0x00,0x00,/*D*/
|
||||
0x00,0xFE,0xFE,0x42,0x42,0x42,0x42,0x42,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x10,0x10,0x10,0x10,0x10,0x00,0x00,0x00,0x00,0x00,0x00,/*E*/
|
||||
0x00,0xFE,0xFE,0x82,0x82,0x82,0x82,0x82,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*F*/
|
||||
0x00,0xF0,0xF8,0x0C,0x06,0x02,0x82,0x82,0x82,0x84,0x00,0x00,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x0C,0x18,0x10,0x10,0x10,0x1F,0x1F,0x00,0x00,0x00,0x00,/*G*/
|
||||
0x00,0xFE,0xFE,0x40,0x40,0x40,0x40,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x00,/*H*/
|
||||
0x00,0x02,0x02,0x02,0xFE,0xFE,0x02,0x02,0x02,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x10,0x10,0x1F,0x1F,0x10,0x10,0x10,0x00,0x00,0x00,0x00,0x00,/*I*/
|
||||
0x00,0x02,0x02,0x02,0x02,0x02,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x08,0x10,0x10,0x10,0x18,0x0F,0x07,0x00,0x00,0x00,0x00,0x00,0x00,/*J*/
|
||||
0x00,0xFE,0xFE,0xC0,0xE0,0x30,0x18,0x0C,0x06,0x02,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x01,0x03,0x06,0x0C,0x18,0x10,0x00,0x00,0x00,0x00,/*K*/
|
||||
0x00,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x10,0x10,0x10,0x10,0x10,0x00,0x00,0x00,0x00,0x00,0x00,/*L*/
|
||||
0x00,0x00,0xFE,0x06,0x3C,0xC0,0xC0,0x3C,0x06,0xFE,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x1F,0x00,0x00,0x01,0x01,0x00,0x00,0x1F,0x18,0x00,0x00,0x00,/*M*/
|
||||
0x00,0xFE,0xFE,0x1E,0x70,0x80,0x00,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x00,0x03,0x1C,0x1F,0x1F,0x00,0x00,0x00,0x00,0x00,/*N*/
|
||||
0x00,0xF0,0xFC,0x0C,0x02,0x02,0x02,0x0E,0xFC,0xF0,0x00,0x00,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x1C,0x10,0x10,0x10,0x0C,0x0F,0x03,0x00,0x00,0x00,0x00,/*O*/
|
||||
0x00,0xFE,0xFE,0x02,0x02,0x02,0x86,0xFC,0x78,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x01,0x01,0x01,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*P*/
|
||||
0x00,0xF0,0xF8,0x0C,0x02,0x02,0x02,0x02,0x0C,0xFC,0xF0,0x00,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x1C,0x10,0x30,0x70,0xD8,0x8C,0x8F,0x83,0x40,0x00,0x00,/*Q*/
|
||||
0x00,0xFE,0xFE,0x42,0x42,0xC2,0xE6,0x3C,0x1C,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x00,0x00,0x01,0x0F,0x1C,0x10,0x00,0x00,0x00,0x00,/*R*/
|
||||
0x00,0x38,0x7C,0x66,0xC2,0xC2,0x82,0x84,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x08,0x10,0x10,0x10,0x10,0x19,0x0F,0x07,0x00,0x00,0x00,0x00,0x00,/*S*/
|
||||
0x00,0x02,0x02,0x02,0x02,0xFE,0xFE,0x02,0x02,0x02,0x02,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*T*/
|
||||
0x00,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,0xFE,0xFE,0x00,0x00,0x00,0x00,
|
||||
0x00,0x07,0x0F,0x18,0x10,0x10,0x10,0x18,0x0F,0x07,0x00,0x00,0x00,0x00,/*U*/
|
||||
0x00,0x0E,0x7E,0xE0,0x00,0x00,0x00,0xE0,0x7C,0x0E,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x03,0x1F,0x18,0x1F,0x03,0x00,0x00,0x00,0x00,0x00,0x00,/*V*/
|
||||
0x00,0x7E,0xFE,0x00,0x00,0xE0,0xE0,0x00,0x00,0xFE,0x7E,0x00,0x00,0x00,
|
||||
0x00,0x00,0x1F,0x18,0x0F,0x01,0x01,0x0F,0x18,0x1F,0x00,0x00,0x00,0x00,/*W*/
|
||||
0x00,0x02,0x06,0x1C,0x38,0xE0,0xE0,0x38,0x1C,0x06,0x02,0x00,0x00,0x00,
|
||||
0x00,0x10,0x18,0x0E,0x07,0x01,0x01,0x07,0x0E,0x18,0x10,0x00,0x00,0x00,/*X*/
|
||||
0x00,0x02,0x0E,0x3C,0xF0,0xC0,0xC0,0xF0,0x3C,0x0E,0x02,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*Y*/
|
||||
0x00,0x02,0x02,0x02,0xC2,0xE2,0x3A,0x0E,0x02,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x1C,0x17,0x11,0x10,0x10,0x10,0x10,0x00,0x00,0x00,0x00,0x00,/*Z*/
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/* */
|
||||
#define FONT_WIDTH 12 /*How many pixels wide the font is*/
|
||||
const uint8_t FONT[]={
|
||||
0x00,0xF0,0xFC,0x0E,0x82,0xC2,0x62,0x1E,0xFC,0xF0,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x1F,0x11,0x10,0x10,0x1C,0x0F,0x03,0x00,0x00,/*0*/
|
||||
0x00,0x08,0x04,0x02,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x10,0x10,0x1F,0x1F,0x10,0x10,0x10,0x00,0x00,0x00,/*1*/
|
||||
0x00,0x04,0x02,0x02,0x02,0xC6,0xFC,0x78,0x00,0x00,0x00,0x00,
|
||||
0x00,0x18,0x1C,0x16,0x13,0x11,0x10,0x10,0x10,0x00,0x00,0x00,/*2*/
|
||||
0x00,0x02,0x02,0x42,0x42,0x66,0xFE,0x9C,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x10,0x10,0x10,0x10,0x08,0x0F,0x07,0x00,0x00,0x00,/*3*/
|
||||
0x00,0x00,0x80,0xE0,0x30,0x1C,0x06,0xFE,0xFE,0x00,0x00,0x00,
|
||||
0x00,0x03,0x03,0x02,0x02,0x02,0x02,0x1F,0x1F,0x02,0x02,0x00,/*4*/
|
||||
0x00,0x7E,0x7E,0x42,0x42,0x42,0xC2,0x82,0x00,0x00,0x00,0x00,
|
||||
0x00,0x10,0x10,0x10,0x10,0x10,0x08,0x0F,0x07,0x00,0x00,0x00,/*5*/
|
||||
0x00,0xE0,0xF8,0x8C,0x44,0x42,0x42,0xC2,0x82,0x80,0x00,0x00,
|
||||
0x00,0x07,0x0F,0x18,0x10,0x10,0x10,0x18,0x0F,0x07,0x00,0x00,/*6*/
|
||||
0x00,0x02,0x02,0x02,0x02,0xC2,0xF2,0x1E,0x06,0x00,0x00,0x00,
|
||||
0x00,0x00,0x10,0x1C,0x0F,0x03,0x00,0x00,0x00,0x00,0x00,0x00,/*7*/
|
||||
0x00,0x38,0x7C,0x66,0xC2,0x82,0xC2,0x66,0x7C,0x3C,0x00,0x00,
|
||||
0x00,0x0E,0x0F,0x19,0x10,0x10,0x10,0x19,0x0F,0x0E,0x00,0x00,/*8*/
|
||||
0x00,0x78,0x7C,0xC6,0x82,0x82,0x82,0x46,0xFC,0xF8,0x00,0x00,
|
||||
0x00,0x00,0x10,0x10,0x10,0x10,0x08,0x0C,0x07,0x03,0x00,0x00,/*9*/
|
||||
|
||||
0x00,0x60,0xF0,0x98,0x0C,0x06,0x02,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x01,0x03,0x06,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*<*/
|
||||
0x00,0x02,0x06,0x0C,0x98,0xF0,0x60,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x04,0x06,0x03,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*>*/
|
||||
0x00,0x00,0x80,0xF0,0x1E,0x02,0x1E,0xF0,0x80,0x00,0x00,0x00,
|
||||
0x00,0x1C,0x0F,0x03,0x02,0x02,0x02,0x03,0x0F,0x1C,0x00,0x00,/*A*/
|
||||
0x00,0xFE,0xFE,0x42,0x42,0x42,0xE6,0xBE,0x9C,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x10,0x10,0x10,0x18,0x0F,0x07,0x00,0x00,0x00,/*B*/
|
||||
0x00,0xF0,0xF8,0x0C,0x06,0x02,0x02,0x02,0x04,0x00,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x0C,0x18,0x10,0x10,0x10,0x08,0x00,0x00,0x00,/*C*/
|
||||
0x00,0xFE,0xFE,0x02,0x02,0x02,0x06,0x0C,0xFC,0xF0,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x10,0x10,0x10,0x18,0x0C,0x07,0x03,0x00,0x00,/*D*/
|
||||
0x00,0xFE,0xFE,0x42,0x42,0x42,0x42,0x42,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x10,0x10,0x10,0x10,0x10,0x00,0x00,0x00,0x00,/*E*/
|
||||
0x00,0xFE,0xFE,0x82,0x82,0x82,0x82,0x82,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*F*/
|
||||
0x00,0xF0,0xF8,0x0C,0x06,0x02,0x82,0x82,0x82,0x84,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x0C,0x18,0x10,0x10,0x10,0x1F,0x1F,0x00,0x00,/*G*/
|
||||
0x00,0xFE,0xFE,0x40,0x40,0x40,0x40,0xFE,0xFE,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x1F,0x1F,0x00,0x00,0x00,/*H*/
|
||||
0x00,0x02,0x02,0x02,0xFE,0xFE,0x02,0x02,0x02,0x00,0x00,0x00,
|
||||
0x00,0x10,0x10,0x10,0x1F,0x1F,0x10,0x10,0x10,0x00,0x00,0x00,/*I*/
|
||||
0x00,0x02,0x02,0x02,0x02,0x02,0xFE,0xFE,0x00,0x00,0x00,0x00,
|
||||
0x00,0x08,0x10,0x10,0x10,0x18,0x0F,0x07,0x00,0x00,0x00,0x00,/*J*/
|
||||
0x00,0xFE,0xFE,0xC0,0xE0,0x30,0x18,0x0C,0x06,0x02,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x01,0x03,0x06,0x0C,0x18,0x10,0x00,0x00,/*K*/
|
||||
0x00,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x10,0x10,0x10,0x10,0x10,0x00,0x00,0x00,0x00,/*L*/
|
||||
0x00,0x00,0xFE,0x06,0x3C,0xC0,0xC0,0x3C,0x06,0xFE,0x00,0x00,
|
||||
0x00,0x10,0x1F,0x00,0x00,0x01,0x01,0x00,0x00,0x1F,0x18,0x00,/*M*/
|
||||
0x00,0xFE,0xFE,0x1E,0x70,0x80,0x00,0xFE,0xFE,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x00,0x03,0x1C,0x1F,0x1F,0x00,0x00,0x00,/*N*/
|
||||
0x00,0xF0,0xFC,0x0C,0x02,0x02,0x02,0x0E,0xFC,0xF0,0x00,0x00,
|
||||
0x00,0x03,0x0F,0x1C,0x10,0x10,0x10,0x0C,0x0F,0x03,0x00,0x00,/*O*/
|
||||
0x00,0xFE,0xFE,0x02,0x02,0x02,0x86,0xFC,0x78,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x01,0x01,0x01,0x01,0x00,0x00,0x00,0x00,0x00,/*P*/
|
||||
0x00,0xF0,0xF8,0x0C,0x02,0x02,0x02,0x02,0x0C,0xFC,0xF0,0x00,
|
||||
0x00,0x03,0x0F,0x1C,0x10,0x30,0x70,0xD8,0x8C,0x8F,0x83,0x40,/*Q*/
|
||||
0x00,0xFE,0xFE,0x42,0x42,0xC2,0xE6,0x3C,0x1C,0x00,0x00,0x00,
|
||||
0x00,0x1F,0x1F,0x00,0x00,0x00,0x01,0x0F,0x1C,0x10,0x00,0x00,/*R*/
|
||||
0x00,0x38,0x7C,0x66,0xC2,0xC2,0x82,0x84,0x00,0x00,0x00,0x00,
|
||||
0x00,0x08,0x10,0x10,0x10,0x10,0x19,0x0F,0x07,0x00,0x00,0x00,/*S*/
|
||||
0x00,0x02,0x02,0x02,0x02,0xFE,0xFE,0x02,0x02,0x02,0x02,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x00,/*T*/
|
||||
0x00,0xFE,0xFE,0x00,0x00,0x00,0x00,0x00,0xFE,0xFE,0x00,0x00,
|
||||
0x00,0x07,0x0F,0x18,0x10,0x10,0x10,0x18,0x0F,0x07,0x00,0x00,/*U*/
|
||||
0x00,0x0E,0x7E,0xE0,0x00,0x00,0x00,0xE0,0x7C,0x0E,0x00,0x00,
|
||||
0x00,0x00,0x00,0x03,0x1F,0x18,0x1F,0x03,0x00,0x00,0x00,0x00,/*V*/
|
||||
0x00,0x7E,0xFE,0x00,0x00,0xE0,0xE0,0x00,0x00,0xFE,0x7E,0x00,
|
||||
0x00,0x00,0x1F,0x18,0x0F,0x01,0x01,0x0F,0x18,0x1F,0x00,0x00,/*W*/
|
||||
0x00,0x02,0x06,0x1C,0x38,0xE0,0xE0,0x38,0x1C,0x06,0x02,0x00,
|
||||
0x00,0x10,0x18,0x0E,0x07,0x01,0x01,0x07,0x0E,0x18,0x10,0x00,/*X*/
|
||||
0x00,0x02,0x0E,0x3C,0xF0,0xC0,0xC0,0xF0,0x3C,0x0E,0x02,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x1F,0x1F,0x00,0x00,0x00,0x00,0x00,/*Y*/
|
||||
0x00,0x02,0x02,0x02,0xC2,0xE2,0x3A,0x0E,0x02,0x00,0x00,0x00,
|
||||
0x00,0x10,0x1C,0x17,0x11,0x10,0x10,0x10,0x10,0x00,0x00,0x00,/*Z*/
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/* */
|
||||
|
||||
0x00,0x60,0xF0,0x98,0x0C,0x06,0x02,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x01,0x03,0x06,0x04,0x00,0x00,0x00,0x00,0x00,/*<*/
|
||||
0x00,0x02,0x06,0x0C,0x98,0xF0,0x60,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x04,0x06,0x03,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*>*/
|
||||
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x0F,0x0F,0x0F,0x0F,0x00,0x00,0x00,0x00,/*.*/
|
||||
};
|
||||
|
||||
const uint8_t Iron_Base[] ={
|
||||
0x00,0x20,0x60,0x60,0x60,0x60,0x60,0x60,0x90,0x90,0x90,0x90,
|
||||
0x90,0x90,0x90,0x90,0x90,0x90,0x90,0x90,0x90,0x90,0x90,0x90,
|
||||
0x90,0x90,0x90,0x90,0x90,0x90,0x90,0x90,0x90,0x60,0x60,0x60,
|
||||
0x60,0x60,0x60,0x60,0x60,0x70,0xF8,0x88,0x84,0x82,0x82,0x83,
|
||||
0x83,0x83,0x83,0x83,0x83,0x82,0x82,0x82,0x82,0x83,0x83,0x83,
|
||||
0x83,0x83,0x83,0x82,0x82,0x82,0x82,0x82,0x86,0x84,0x84,0x84,
|
||||
0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,
|
||||
0x84,0x84,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0xFE,0x00,
|
||||
|
||||
};
|
||||
//The top pixel row for left arrow / on hint
|
||||
const uint8_t Iron_LeftArrow_UP[] = {
|
||||
0x00,0x7C,0x82,0x82,0x82,0x7C,0x00,0xFE,0x08,0x10,0x20,0xFE,//ON
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x88,
|
||||
0x98,0xBF,0xBF,0x98,0x88,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
};
|
||||
|
||||
const uint8_t Iron_LeftArrow_DOWN[] = {
|
||||
0x00,0x7C,0x82,0x82,0x82,0x7C,0x00,0xFE,0x08,0x10,0x20,0xFE,//ON
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x10,
|
||||
0x30,0x7E,0x7E,0x30,0x10,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
};
|
||||
//The top pixel row for both arrows /
|
||||
const uint8_t Iron_BothArrows[] = {
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x88,
|
||||
0x98,0xBF,0xBF,0x98,0x88,0x00,0x00,0x00,0x00,0x88,0x98,0xBF,
|
||||
0xBF,0x98,0x88,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
};
|
||||
//The top pixel row for right arrow / settings hint
|
||||
const uint8_t Iron_RightArrow_UP[] = {
|
||||
0x00,0x8C,0x92,0x92,0x92,0x62,0x00,0xFE,0x92,0x92,0x92,0x82,//SE
|
||||
0x00,0x02,0x02,0xFE,0x02,0x02,0x00,0x02,0x02,0xFE,0x02,0x02,//TT
|
||||
0x00,0x00,0x82,0xFE,0x82,0x00,0x00,0xFE,0x08,0x10,0x20,0xFE,//IN
|
||||
0x00,0x7C,0x82,0x82,0xA2,0x62,0x00,0x8C,0x92,0x92,0x92,0x62,//GS
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x88,0x98,0xBF,
|
||||
0xBF,0x98,0x88,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
};
|
||||
const uint8_t Iron_RightArrow_DOWN[] = {
|
||||
0x00,0x8C,0x92,0x92,0x92,0x62,0x00,0xFE,0x92,0x92,0x92,0x82,//SE
|
||||
0x00,0x02,0x02,0xFE,0x02,0x02,0x00,0x02,0x02,0xFE,0x02,0x02,//TT
|
||||
0x00,0x00,0x82,0xFE,0x82,0x00,0x00,0xFE,0x08,0x10,0x20,0xFE,//IN
|
||||
0x00,0x7C,0x82,0x82,0xA2,0x62,0x00,0x8C,0x92,0x92,0x92,0x62,//GS
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x10,0x30,0x7E,
|
||||
0x7E,0x30,0x10,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||
};
|
||||
|
||||
const uint8_t SymbolTable[]={
|
||||
|
||||
0x0E,0x11,0x11,0x0E,0xE0,0xF8,0x0C,0x06,0x03,0x01,0x01,0x01,0x01,0x02,0x1E,0x00,
|
||||
0x00,0x00,0x00,0x00,0x0F,0x3F,0x70,0xC0,0x80,0x80,0x80,0x80,0x80,0x40,0x20,0x00, // Degrees C
|
||||
|
||||
0x08,0x14,0x22,0x14,0x08,0x02,0x02,0xFE,0x06,0x02,0x02,0x02,0xC2,0x02,0x06,0x1E,
|
||||
0x00,0x00,0x00,0x00,0x00,0x80,0x80,0xFF,0x81,0x81,0x01,0x01,0x03,0x00,0x00,0x00, // Degrees F
|
||||
|
||||
0xC0,0x30,0x08,0x04,0x04,0x02,0xFA,0xAA,0xFA,0x02,0x04,0x04,0x08,0x30,0xC0,0x00,
|
||||
0x07,0x18,0x20,0x40,0x58,0xA4,0xDB,0xDE,0xDB,0xA4,0x58,0x40,0x20,0x18,0x07,0x00, // Temp symbol
|
||||
|
||||
0x00,0xF0,0xF0,0x00,0x00,0xF0,0xF0,0xF0,0x00,0x00,0xFC,0xF8,0xF0,0xE0,0xC0,0x80, //Right Arrow
|
||||
0x00,0x0F,0x0F,0x00,0x00,0x0F,0x0F,0x0F,0x00,0x00,0x3F,0x1F,0x0F,0x07,0x03,0x01,
|
||||
|
||||
0x80,0xC0,0xE0,0xF0,0xF8,0xFC,0x00,0x00,0xF0,0xF0,0xF0,0x00,0x00,0xF0,0xF0,0x00, //Left Arrow
|
||||
0x01,0x03,0x07,0x0F,0x1F,0x3F,0x00,0x00,0x0F,0x0F,0x0F,0x00,0x00,0x0F,0x0F,0x00,
|
||||
|
||||
0x11,0x33,0x66,0xCC,0x98,0x30,0x60,0xC0,0xC0,0x60,0x30,0x98,0xCC,0x66,0x33,0x11,
|
||||
0x01,0x03,0x06,0x0C,0x19,0x33,0x66,0xCC,0xCC,0x66,0x33,0x19,0x0C,0x06,0x03,0x01, //Down Chevron
|
||||
|
||||
0x80,0xC0,0x60,0x30,0x98,0xCC,0x66,0x33,0x33,0x66,0xCC,0x98,0x30,0x60,0xC0,0x80,
|
||||
0x88,0xCC,0x66,0x33,0x19,0x0C,0x06,0x03,0x03,0x06,0x0C,0x19,0x33,0x66,0xCC,0x88, //Up Chevron
|
||||
|
||||
0x00,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x8C,0x00, // Flat Lines
|
||||
0x00,0x31,0x31,0x31,0x31,0x31,0x31,0x31,0x31,0x31,0x31,0x31,0x31,0x31,0x31,0x00,
|
||||
};
|
||||
#endif /* FONT_H_ */
|
||||
|
||||
@@ -15,7 +15,7 @@
|
||||
#define __MMA8652FC__H
|
||||
|
||||
|
||||
void StartUp_Accelerometer(void);//This is the only function we expose
|
||||
void StartUp_Accelerometer(uint8_t sensitivity);//This is the only function we expose
|
||||
|
||||
//--------------MMA8652 Device ID----------------------------------------------//
|
||||
|
||||
|
||||
@@ -17,18 +17,28 @@
|
||||
#include "Settings.h"
|
||||
#include "Analog.h"
|
||||
enum {
|
||||
STARTUP, //we are sitting on the prompt to push a button
|
||||
SOLDERING,
|
||||
TEMP_ADJ,
|
||||
SETTINGS,
|
||||
SLEEP,
|
||||
COOLING,
|
||||
UVLOWARN,
|
||||
STARTUP, //we are sitting on the prompt to push a button
|
||||
SOLDERING, //Normal operating mode
|
||||
TEMP_ADJ, //Adjust the set temperature
|
||||
SETTINGS, //Settings menu
|
||||
SLEEP, //Iron is snoozing due to lack of use
|
||||
COOLING, //Iron is cooling down -> Warning screen
|
||||
UVLOWARN, //Unit tripped low voltage
|
||||
THERMOMETER, //Read the tip temp
|
||||
DCINDISP, //Disp the input voltage && Cal the DCin voltage divider
|
||||
TEMPCAL, //Cal tip temp offset
|
||||
|
||||
} operatingMode;
|
||||
|
||||
enum {
|
||||
UVLO = 0, SLEEP_TEMP, SLEEP_TIME,MOTIONDETECT,
|
||||
|
||||
UVCO = 0,
|
||||
SLEEP_TEMP,
|
||||
SLEEP_TIME,
|
||||
SHUTDOWN_TIME,
|
||||
MOTIONDETECT,
|
||||
MOTIONSENSITIVITY,
|
||||
TEMPDISPLAY,
|
||||
LEFTY,
|
||||
} settingsPage;
|
||||
|
||||
void ProcessUI();
|
||||
|
||||
@@ -16,16 +16,18 @@ void Oled_DisplayOff(void);
|
||||
|
||||
u8* Oled_DrawArea(u8 x0, u8 y0, u8 wide, u8 high, u8* ptr);
|
||||
void Set_ShowPos(u8 x, u8 y);
|
||||
|
||||
void Oled_DisplayFlip();
|
||||
void GPIO_Init_OLED(void);
|
||||
void Init_Oled(void);
|
||||
void Init_Oled(uint8_t leftHanded);
|
||||
u8* Data_Command(u8 len, u8* ptr);
|
||||
void Clear_Screen(void);//Clear the screen
|
||||
/*Functions for writing to the screen*/
|
||||
void OLED_DrawString(char* string, uint8_t length);
|
||||
void OLED_DrawChar(char c, uint8_t x);
|
||||
void OLED_DrawTwoNumber(uint8_t in, uint8_t x);
|
||||
void OLED_BlankSlot(uint8_t xStart,uint8_t width);
|
||||
void OLED_DrawThreeNumber(uint16_t in, uint8_t x);
|
||||
|
||||
void OLED_DrawIDLELogo();
|
||||
void OLED_DrawSymbol(uint8_t x,uint8_t symbol);
|
||||
#endif
|
||||
/******************************** END OF FILE *********************************/
|
||||
|
||||
@@ -11,16 +11,28 @@
|
||||
#define SETTINGS_H_
|
||||
#include <stdint.h>
|
||||
#include "stm32f10x_flash.h"
|
||||
#define SETTINGSVERSION 0x01 /*Change this if you change the struct below to prevent people getting out of sync*/
|
||||
#define SETTINGSVERSION 0x05 /*Change this if you change the struct below to prevent people getting out of sync*/
|
||||
#define SETTINGSOPTIONSCOUNT 7 /*Number of settings in the settings menu*/
|
||||
#define MOTION_HIGH (0x00)
|
||||
#define MOTION_MED (0x10)
|
||||
#define MOTION_LOW (0x20)
|
||||
/*
|
||||
* This struct must be a multiple of 2 bytes as it is saved / restored from flash in uint16_t chunks
|
||||
*/
|
||||
struct {
|
||||
uint32_t SolderingTemp; //current setpoint for the iron
|
||||
uint32_t SleepTemp; //temp to drop to in sleep
|
||||
uint8_t SleepTime; //minutes to sleep
|
||||
uint8_t cutoutVoltage; //X10 the voltage we cutout at for undervoltage
|
||||
uint8_t movementEnabled;
|
||||
uint8_t version;
|
||||
uint32_t SolderingTemp; //current set point for the iron
|
||||
uint32_t SleepTemp; //temp to drop to in sleep
|
||||
uint8_t version; //Used to track if a reset is needed on firmware upgrade
|
||||
uint8_t SleepTime; //minutes timeout to sleep
|
||||
uint8_t cutoutVoltage:5; //The voltage we cut out at for under voltage
|
||||
uint8_t movementEnabled:1; //If movement is enabled
|
||||
uint8_t displayTempInF:1; //If we need to convert the C reading to F
|
||||
uint8_t flipDisplay:1; //If true we want to invert the display for lefties
|
||||
uint8_t sensitivity:7; //Sensitivity of accelerometer
|
||||
uint8_t ShutdownTime:7; //Time until unit shuts down if left alone
|
||||
uint16_t tempCalibration; //Temperature calibration value
|
||||
uint16_t voltageDiv; //Voltage divisor factor
|
||||
} systemSettings;
|
||||
//Settings struct used for user settings
|
||||
|
||||
void saveSettings();
|
||||
void restoreSettings();
|
||||
|
||||
@@ -10,12 +10,12 @@
|
||||
|
||||
//Reads the dc input and returns it as X10 voltage (ie 236 = 23.6V)
|
||||
//Seems unstable below 9.5V input
|
||||
uint16_t readDCVoltage() {
|
||||
uint16_t readDCVoltage(uint16_t divFactor) {
|
||||
uint16_t reading = 0;
|
||||
for (u8 i = 0; i < 10; i++) {
|
||||
reading += ADC_GetConversionValue(ADC2);
|
||||
}
|
||||
reading /= 144; //take the average and convert to X10 voltage
|
||||
reading /= divFactor; //take the average and convert to X10 voltage
|
||||
return reading; //return the read voltage
|
||||
}
|
||||
|
||||
@@ -105,16 +105,30 @@ uint16_t Get_ADC1Value(uint8_t i) {
|
||||
}
|
||||
//This returns the calibrated temperature reading of the iron temp
|
||||
//inputs : calibration value / wether to take a new reading or not
|
||||
uint16_t readIronTemp(uint16_t calibration_temp, uint8_t read) {
|
||||
uint16_t readIronTemp(uint16_t calibration_temp, uint8_t read,
|
||||
uint16_t setPointTemp) {
|
||||
static uint16_t calTemp = 0;
|
||||
static uint16_t lastVal = 0;
|
||||
|
||||
static uint16_t lastSetTemp;
|
||||
if(setPointTemp!=0xFFFF)
|
||||
lastSetTemp = setPointTemp;
|
||||
if (calibration_temp != 0)
|
||||
calTemp = calibration_temp;
|
||||
|
||||
if (read) {
|
||||
lastVal = (readTipTemp() * 1000 + 806 * readSensorTemp()
|
||||
- calTemp * 1000) / 806;
|
||||
int16_t compensation = 80 + 150 * (lastSetTemp - 1000) / 3000;
|
||||
int16_t tipTemp = readTipTemp();
|
||||
int16_t ColdJTemp = readSensorTemp();
|
||||
if (lastSetTemp == 1000)
|
||||
compensation -= 10;
|
||||
|
||||
if (lastSetTemp != 0) {
|
||||
if (tipTemp > (compensation + calTemp))
|
||||
tipTemp -= compensation;
|
||||
}
|
||||
if (ColdJTemp > 400)
|
||||
ColdJTemp = 400;
|
||||
lastVal = (tipTemp * 1000 + 807 * ColdJTemp - calTemp * 1000) / 807;
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -22,7 +22,7 @@ void I2C_Configuration(void) {
|
||||
I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
|
||||
I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
I2C_InitStructure.I2C_ClockSpeed = 100000; //100k
|
||||
I2C_InitStructure.I2C_ClockSpeed = 400000; //400k
|
||||
I2C_Init(I2C1, &I2C_InitStructure);
|
||||
I2C_Cmd(I2C1, ENABLE);
|
||||
}
|
||||
|
||||
@@ -53,7 +53,7 @@ void TIM3_IRQHandler(void) {
|
||||
//used for buttons and movement
|
||||
void EXTI9_5_IRQHandler(void) {
|
||||
//we are interested in line 9 and line 6 for buttons
|
||||
//Lien 5 == movement
|
||||
//Line 5 == movement
|
||||
if (EXTI_GetITStatus(EXTI_Line9) != RESET) {
|
||||
if (GPIO_ReadInputDataBit(GPIOA, KEY_A) == SET)
|
||||
keyState &= ~(BUT_A);
|
||||
|
||||
@@ -29,15 +29,15 @@ uint8_t I2C_RegisterRead(uint8_t reg) {
|
||||
return tx_data[0];
|
||||
}
|
||||
|
||||
void StartUp_Accelerometer(void) {
|
||||
void StartUp_Accelerometer(uint8_t sensitivity) {
|
||||
I2C_RegisterWrite(CTRL_REG2, 0); //Normal mode
|
||||
I2C_RegisterWrite( CTRL_REG2, 0x40); // Reset all registers to POR values
|
||||
delayMs(2); // ~1ms delay
|
||||
I2C_RegisterWrite(FF_MT_CFG_REG, 0x78); // Enable motion detection for X and Y axis, latch enabled
|
||||
I2C_RegisterWrite(FF_MT_THS_REG, 0x0F); // Set threshold
|
||||
I2C_RegisterWrite(FF_MT_THS_REG, sensitivity|0x0F); // Set threshold
|
||||
I2C_RegisterWrite(FF_MT_COUNT_REG, 0x01); // Set debounce to 100ms
|
||||
|
||||
I2C_RegisterWrite( CTRL_REG4, 0x04); // Enable motion interrupt
|
||||
I2C_RegisterWrite( CTRL_REG5, 0x04);// Route motion interrupts to INT1 ->PB5 ->EXTI
|
||||
I2C_RegisterWrite( CTRL_REG5, 0x04);// Route motion interrupts to INT1 ->PB5 ->EXTI5
|
||||
I2C_RegisterWrite( CTRL_REG1, 0x19); // ODR=100 Hz, Active mode
|
||||
}
|
||||
|
||||
@@ -12,30 +12,32 @@
|
||||
void setup();
|
||||
|
||||
int main(void) {
|
||||
setup();
|
||||
setup();/*Setup the system*/
|
||||
while (1) {
|
||||
Clear_Watchdog(); //reset the Watchdog
|
||||
Clear_Watchdog(); //reset the Watch dog timer
|
||||
ProcessUI();
|
||||
DrawUI();
|
||||
delayMs(50);
|
||||
delayMs(50); //Slow the system down a little bit
|
||||
}
|
||||
}
|
||||
void setup()
|
||||
{
|
||||
RCC_Config(); //setup system clock
|
||||
NVIC_Config(0x4000); //this shifts the NVIC table to be offset, for the usb bootloader's size
|
||||
GPIO_Config(); //setup all the GPIO pins
|
||||
Init_EXTI(); //init the EXTI inputs
|
||||
Init_Timer3(); //Used for the soldering iron tip
|
||||
Adc_Init(); //init adc and dma
|
||||
I2C_Configuration(); //Start the I2C hardware
|
||||
GPIO_Init_OLED(); //Init the GPIO ports for the OLED
|
||||
StartUp_Accelerometer(); //start the accelerometer
|
||||
Init_Oled(); //init the OLED display
|
||||
Clear_Screen(); //clear the display buffer to black
|
||||
setupPID(); //init the PID values
|
||||
readIronTemp(239, 0); //load the default calibration value
|
||||
restoreSettings(); //Load settings
|
||||
void setup() {
|
||||
RCC_Config(); //setup system clock
|
||||
NVIC_Config(0x4000); //this shifts the NVIC table to be offset, for the usb bootloader's size
|
||||
GPIO_Config(); //setup all the GPIO pins
|
||||
Init_EXTI(); //Init the EXTI inputs
|
||||
Init_Timer3(); //Used for the soldering iron tip
|
||||
Adc_Init(); //Init adc and DMA
|
||||
I2C_Configuration(); //Start the I2C hardware
|
||||
GPIO_Init_OLED(); //Init the GPIO ports for the OLED
|
||||
restoreSettings(); //Load settings
|
||||
|
||||
Start_Watchdog(1000); //start the system watchdog as 1 seconds timeout
|
||||
StartUp_Accelerometer(systemSettings.sensitivity); //start the accelerometer
|
||||
|
||||
setupPID(); //Init the PID values
|
||||
readIronTemp(systemSettings.tempCalibration, 0,0); //load the default calibration value
|
||||
Init_Oled(systemSettings.flipDisplay); //Init the OLED display
|
||||
|
||||
OLED_DrawString("VER 1.08", 8); //
|
||||
delayMs(800); //Pause to show version number
|
||||
Start_Watchdog(1000); //start the system watch dog as 1 second timeout
|
||||
}
|
||||
|
||||
@@ -5,43 +5,41 @@
|
||||
* Author: Ralim <ralim@ralimtek.com>
|
||||
*/
|
||||
#include "Modes.h"
|
||||
uint8_t CalStatus = 0;
|
||||
//This does the required processing and state changes
|
||||
void ProcessUI() {
|
||||
uint8_t Buttons = getButtons(); //read the buttons status
|
||||
static uint32_t lastModeChange = 0;
|
||||
if (millis() - getLastButtonPress() < 200)
|
||||
if (millis() - getLastButtonPress() < 30)
|
||||
Buttons = 0;
|
||||
else if (Buttons != 0) {
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
}
|
||||
//rough prevention for de-bouncing and allocates settling time
|
||||
|
||||
switch (operatingMode) {
|
||||
case STARTUP:
|
||||
if ((millis() - getLastButtonPress() > 1000)) {
|
||||
if (Buttons & BUT_A) {
|
||||
//A key pressed so we are moving to soldering mode
|
||||
operatingMode = SOLDERING;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
} else if (Buttons & BUT_B) {
|
||||
//B Button was pressed so we are moving to the Settings menu
|
||||
operatingMode = SETTINGS;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
}
|
||||
if (Buttons == (BUT_A | BUT_B)) {
|
||||
operatingMode = THERMOMETER;
|
||||
} else if (Buttons == BUT_A) {
|
||||
//A key pressed so we are moving to soldering mode
|
||||
operatingMode = SOLDERING;
|
||||
} else if (Buttons == BUT_B) {
|
||||
//B Button was pressed so we are moving to the Settings menu
|
||||
operatingMode = SETTINGS;
|
||||
}
|
||||
//Nothing else to check here
|
||||
break;
|
||||
case SOLDERING:
|
||||
//We need to check the buttons if we need to jump out
|
||||
if (Buttons & BUT_A) {
|
||||
//A key pressed so we are moving to temp set
|
||||
if (Buttons == BUT_A || Buttons == BUT_B) {
|
||||
//A or B key pressed so we are moving to temp set
|
||||
operatingMode = TEMP_ADJ;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
} else if (Buttons & BUT_B) {
|
||||
//B Button was pressed so we are moving back to idle
|
||||
} else if (Buttons == (BUT_A | BUT_B)) {
|
||||
|
||||
//Both buttons were pressed, exit back to the cooling screen
|
||||
operatingMode = COOLING;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
|
||||
} else {
|
||||
//We need to check the timer for movement in case we need to goto idle
|
||||
if (systemSettings.movementEnabled)
|
||||
@@ -53,65 +51,59 @@ void ProcessUI() {
|
||||
return;
|
||||
}
|
||||
}
|
||||
uint16_t voltage = readDCVoltage(); //get X10 voltage
|
||||
uint16_t voltage = readDCVoltage(systemSettings.voltageDiv); //get X10 voltage
|
||||
if ((voltage / 10) < systemSettings.cutoutVoltage) {
|
||||
operatingMode = UVLOWARN;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
lastModeChange = millis();
|
||||
}
|
||||
//If no buttons pushed we need to perform the PID loop for the iron temp
|
||||
//Update the PID Loop
|
||||
int32_t newOutput = computePID(systemSettings.SolderingTemp);
|
||||
|
||||
setIronTimer(newOutput);
|
||||
|
||||
setIronTimer(newOutput);
|
||||
}
|
||||
break;
|
||||
case TEMP_ADJ:
|
||||
if (Buttons & BUT_A) {
|
||||
if (Buttons == BUT_A) {
|
||||
//A key pressed so we are moving down in temp
|
||||
resetLastButtonPress();
|
||||
|
||||
if (systemSettings.SolderingTemp > 1000)
|
||||
systemSettings.SolderingTemp -= 100;
|
||||
} else if (Buttons & BUT_B) {
|
||||
} else if (Buttons == BUT_B) {
|
||||
//B key pressed so we are moving up in temp
|
||||
resetLastButtonPress();
|
||||
if (systemSettings.SolderingTemp < 4500)
|
||||
systemSettings.SolderingTemp += 100;
|
||||
} else {
|
||||
//we check the timeout for how long the buttons have not been pushed
|
||||
//if idle for > 3 seconds then we return to soldering
|
||||
if (millis() - getLastButtonPress() > 3000)
|
||||
//Or if both buttons pressed
|
||||
if ((millis() - getLastButtonPress() > 2000)
|
||||
|| Buttons == (BUT_A | BUT_B)) {
|
||||
operatingMode = SOLDERING;
|
||||
saveSettings();
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SETTINGS:
|
||||
//Settings is the mode with the most logic
|
||||
//Here we are in the menu so we need to increment through the sub menus / increase the value
|
||||
if (millis() - getLastButtonPress() < 400)
|
||||
return;
|
||||
|
||||
if (Buttons & BUT_A) {
|
||||
resetLastButtonPress();
|
||||
//A key iterates through the menu
|
||||
if (settingsPage == 3) {
|
||||
if (settingsPage == SETTINGSOPTIONSCOUNT) {
|
||||
//Roll off the end
|
||||
settingsPage = 0; //reset
|
||||
operatingMode = STARTUP;
|
||||
saveSettings(); //Save the settings
|
||||
settingsPage = 0; //reset
|
||||
operatingMode = STARTUP; //reset back to the startup
|
||||
saveSettings(); //Save the settings
|
||||
} else
|
||||
++settingsPage; //move to the next option
|
||||
++settingsPage; //move to the next option
|
||||
} else if (Buttons & BUT_B) {
|
||||
resetLastButtonPress();
|
||||
//B changes the value selected
|
||||
switch (settingsPage) {
|
||||
case UVLO:
|
||||
case UVCO:
|
||||
//we are incrementing the cutout voltage
|
||||
systemSettings.cutoutVoltage += 1; //Go up 1V at a jump
|
||||
if (systemSettings.cutoutVoltage > 24)
|
||||
systemSettings.cutoutVoltage = 9;
|
||||
else if (systemSettings.cutoutVoltage < 9)
|
||||
systemSettings.cutoutVoltage = 9; //cant set UVLO below 9V
|
||||
systemSettings.cutoutVoltage = 10;
|
||||
break;
|
||||
case SLEEP_TEMP:
|
||||
systemSettings.SleepTemp += 100; //Go up 10c at a time
|
||||
@@ -120,14 +112,31 @@ void ProcessUI() {
|
||||
break;
|
||||
case SLEEP_TIME:
|
||||
++systemSettings.SleepTime; //Go up 1 minute at a time
|
||||
if (systemSettings.SleepTime > 60)
|
||||
systemSettings.SleepTime = 2; //cant set time over an hour
|
||||
if (systemSettings.SleepTime > 30)
|
||||
systemSettings.SleepTime = 1; //cant set time over 30 mins
|
||||
//Remember that ^ is the time of no movement
|
||||
break;
|
||||
case SHUTDOWN_TIME:
|
||||
++systemSettings.ShutdownTime;
|
||||
if (systemSettings.ShutdownTime > 60)
|
||||
systemSettings.ShutdownTime = 0; //wrap to off
|
||||
break;
|
||||
case MOTIONDETECT:
|
||||
systemSettings.movementEnabled =
|
||||
!systemSettings.movementEnabled;
|
||||
break;
|
||||
case TEMPDISPLAY:
|
||||
systemSettings.displayTempInF = !systemSettings.displayTempInF;
|
||||
break;
|
||||
case LEFTY:
|
||||
systemSettings.flipDisplay = !systemSettings.flipDisplay;
|
||||
break;
|
||||
case MOTIONSENSITIVITY:
|
||||
systemSettings.sensitivity += 0x10;
|
||||
if (systemSettings.sensitivity > 0x20)
|
||||
systemSettings.sensitivity = 0; //reset to high on wrap
|
||||
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@@ -138,44 +147,42 @@ void ProcessUI() {
|
||||
if (Buttons & BUT_A) {
|
||||
//A Button was pressed so we are moving back to soldering
|
||||
operatingMode = SOLDERING;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
Oled_DisplayOn();
|
||||
return;
|
||||
} else if (Buttons & BUT_B) {
|
||||
//B Button was pressed so we are moving back to soldering
|
||||
operatingMode = SOLDERING;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
Oled_DisplayOn();
|
||||
return;
|
||||
} else if (systemSettings.movementEnabled)
|
||||
if (millis() - getLastMovement() < 1000) {//moved in the last second
|
||||
operatingMode = SOLDERING; //Goto active mode again
|
||||
Oled_DisplayOn();
|
||||
return;
|
||||
}
|
||||
if (systemSettings.movementEnabled) {
|
||||
//Check if we should shutdown
|
||||
if ((millis() - getLastMovement()
|
||||
> (systemSettings.ShutdownTime * 60000))
|
||||
|| (millis() - getLastButtonPress()
|
||||
> systemSettings.ShutdownTime * 60000)) {
|
||||
operatingMode = COOLING; //shutdown the tip
|
||||
Oled_DisplayOn();
|
||||
}
|
||||
}
|
||||
//else if nothing has been pushed we need to compute the PID to keep the iron at the sleep temp
|
||||
int32_t newOutput = computePID(systemSettings.SleepTemp);
|
||||
|
||||
setIronTimer(newOutput);
|
||||
|
||||
setIronTimer(newOutput);
|
||||
break;
|
||||
case COOLING: {
|
||||
setIronTimer(0); //turn off heating
|
||||
//This mode warns the user the iron is still cooling down
|
||||
uint16_t temp = readIronTemp(0, 1); //take a new reading as the heater code is not taking new readings
|
||||
if (temp < 500) { //if the temp is < 50C then we can go back to IDLE
|
||||
uint16_t temp = readIronTemp(0, 1, 0xFFFF); //take a new reading as the heater code is not taking new readings
|
||||
if (temp < 400) { //if the temp is < 40C then we can go back to IDLE
|
||||
operatingMode = STARTUP;
|
||||
} else if (Buttons & (BUT_A | BUT_B)) { //we check if the user has pushed a button to ack
|
||||
//Either button was pushed
|
||||
operatingMode = STARTUP;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
} else { //we check if the user has pushed a button to ack
|
||||
if ((millis() - getLastButtonPress() > 200)
|
||||
&& (millis() - getLastButtonPress() < 2000)) {
|
||||
if (getButtons() && (BUT_A | BUT_B)) {
|
||||
//A button was pushed
|
||||
operatingMode = STARTUP;
|
||||
resetLastButtonPress();
|
||||
resetButtons();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
@@ -186,13 +193,102 @@ void ProcessUI() {
|
||||
operatingMode = STARTUP; //jump back to idle mode
|
||||
}
|
||||
break;
|
||||
case THERMOMETER: {
|
||||
//This lets the user check the tip temp without heating the iron.. And eventually calibration will be added here
|
||||
|
||||
if (Buttons == BUT_A) {
|
||||
//Single button press, cycle over to the DC display
|
||||
CalStatus = 0;
|
||||
operatingMode = DCINDISP;
|
||||
} else if (Buttons == BUT_B) {
|
||||
CalStatus = 0;
|
||||
operatingMode = TEMPCAL;
|
||||
} else if (Buttons == (BUT_A | BUT_B)) {
|
||||
//If the user is holding both button, exit the screen
|
||||
operatingMode = STARTUP;
|
||||
}
|
||||
|
||||
}
|
||||
break;
|
||||
case DCINDISP: {
|
||||
//This lets the user check the input voltage
|
||||
if (CalStatus == 0) {
|
||||
if (Buttons == BUT_A) {
|
||||
//Single button press, cycle over to the temp display
|
||||
operatingMode = THERMOMETER;
|
||||
} else if (Buttons == BUT_B) {
|
||||
//dc cal mode
|
||||
CalStatus = 1;
|
||||
} else if (Buttons == (BUT_A | BUT_B)) {
|
||||
//If the user is holding both button, exit the screen
|
||||
operatingMode = STARTUP;
|
||||
}
|
||||
} else {
|
||||
//User is calibrating the dc input
|
||||
if (Buttons == BUT_A) {
|
||||
if (!systemSettings.flipDisplay)
|
||||
systemSettings.voltageDiv++;
|
||||
else
|
||||
systemSettings.voltageDiv--;
|
||||
} else if (Buttons == BUT_B) {
|
||||
if (!systemSettings.flipDisplay)
|
||||
systemSettings.voltageDiv--;
|
||||
else
|
||||
systemSettings.voltageDiv++;
|
||||
} else if (Buttons == (BUT_A | BUT_B)) {
|
||||
CalStatus = 0;
|
||||
saveSettings();
|
||||
}
|
||||
if (systemSettings.voltageDiv < 120)
|
||||
systemSettings.voltageDiv = 160;
|
||||
else if (systemSettings.voltageDiv > 160)
|
||||
systemSettings.voltageDiv = 120;
|
||||
}
|
||||
|
||||
}
|
||||
break;
|
||||
case TEMPCAL: {
|
||||
if (Buttons == BUT_B) {
|
||||
//Single button press, cycle over to the DC IN
|
||||
operatingMode = THERMOMETER;
|
||||
} else if (Buttons == BUT_A) {
|
||||
//Try and calibrate
|
||||
if (CalStatus == 0) {
|
||||
if ((readTipTemp() < 300) && (readSensorTemp() < 300)) {
|
||||
CalStatus = 1;
|
||||
systemSettings.tempCalibration = readTipTemp();
|
||||
saveSettings();
|
||||
} else {
|
||||
CalStatus = 2;
|
||||
}
|
||||
}
|
||||
} else if (Buttons == (BUT_A | BUT_B)) {
|
||||
//If the user is holding both button, exit the screen
|
||||
operatingMode = STARTUP;
|
||||
}
|
||||
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
/*
|
||||
* Draws the temp with temp conversion if needed
|
||||
*/
|
||||
void drawTemp(uint16_t temp, uint8_t x) {
|
||||
if (systemSettings.displayTempInF)
|
||||
temp = (temp * 9 + 1600) / 5;/*Convert to F -> T*(9/5)+32*/
|
||||
if (temp % 10 > 5)
|
||||
temp += 10; //round up
|
||||
OLED_DrawThreeNumber(temp / 10, x);
|
||||
}
|
||||
|
||||
/*
|
||||
* Performs all the OLED drawing for the current operating mode
|
||||
*/
|
||||
void DrawUI() {
|
||||
uint16_t temp = readIronTemp(0, 0) / 10;
|
||||
uint16_t temp = readIronTemp(0, 0, 0xFFFF);
|
||||
switch (operatingMode) {
|
||||
case STARTUP:
|
||||
//We are chilling in the idle mode
|
||||
@@ -203,61 +299,103 @@ void DrawUI() {
|
||||
Oled_DisplayOff();
|
||||
} else {
|
||||
Oled_DisplayOn();
|
||||
OLED_DrawString("IDLE ", 7); //write the word IDLE
|
||||
OLED_DrawIDLELogo(); //Draw the icons for prompting the user
|
||||
}
|
||||
break;
|
||||
case SOLDERING:
|
||||
//The user is soldering
|
||||
{
|
||||
drawTemp(temp, 0);
|
||||
OLED_DrawChar(' ', 3);
|
||||
|
||||
OLED_BlankSlot(6 * 12 + 16, 24 - 16);//blank out the tail after the arrows
|
||||
OLED_BlankSlot(4 * 12 + 16, 24 - 16);//blank out the tail after the temp
|
||||
if (getIronTimer() == 0) {
|
||||
OLED_DrawChar('C', 14 * 4);
|
||||
OLED_DrawSymbol(6, 5);
|
||||
} else {
|
||||
if (getIronTimer() < 500) {
|
||||
OLED_DrawChar(' ', 14 * 4);
|
||||
if (getIronTimer() < 900) {
|
||||
OLED_DrawSymbol(6, 7);
|
||||
} else { //we are heating
|
||||
OLED_DrawChar('H', 14 * 4);
|
||||
//OLED_DrawChar('H', 5);
|
||||
OLED_DrawSymbol(6, 6);
|
||||
}
|
||||
}
|
||||
OLED_DrawThreeNumber(temp, 0);
|
||||
OLED_DrawChar(' ', 14 * 3);
|
||||
OLED_DrawChar(' ', 14 * 5);
|
||||
OLED_DrawChar(' ', 14 * 6);
|
||||
if (systemSettings.displayTempInF) {
|
||||
OLED_DrawSymbol(4, 1);
|
||||
} else {
|
||||
OLED_DrawSymbol(4, 0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TEMP_ADJ:
|
||||
//We are prompting the user to change the temp so we draw the current setpoint temp
|
||||
//With the nifty arrows
|
||||
OLED_DrawChar('<', 0);
|
||||
OLED_DrawThreeNumber(systemSettings.SolderingTemp / 10, 14 * 1);
|
||||
OLED_DrawChar(' ', 14 * 4);
|
||||
OLED_DrawChar('>', 14 * 5);
|
||||
OLED_DrawChar(' ', 0);
|
||||
OLED_DrawChar('<', 1);
|
||||
drawTemp(systemSettings.SolderingTemp, 2);
|
||||
OLED_DrawChar(' ', 5);
|
||||
OLED_DrawChar(' ', 7);
|
||||
OLED_DrawChar('>', 6);
|
||||
break;
|
||||
case SETTINGS:
|
||||
//We are prompting the user the setting name
|
||||
|
||||
switch (settingsPage) {
|
||||
case UVLO:
|
||||
OLED_DrawString("UVLO", 4);
|
||||
OLED_DrawTwoNumber(systemSettings.cutoutVoltage, 14 * 4);
|
||||
//OLED_DrawChar('V', 14 * 5);
|
||||
|
||||
case UVCO:
|
||||
OLED_DrawString("UVCO ", 5);
|
||||
OLED_DrawTwoNumber(systemSettings.cutoutVoltage, 5);
|
||||
OLED_DrawChar('V', 7);
|
||||
break;
|
||||
case SLEEP_TEMP:
|
||||
OLED_DrawString("STMP", 4);
|
||||
OLED_DrawThreeNumber(systemSettings.SleepTemp / 10, 14 * 4);
|
||||
//OLED_DrawChar('V', 14 * 5);
|
||||
|
||||
OLED_DrawString("STMP ", 5);
|
||||
OLED_DrawThreeNumber(systemSettings.SleepTemp / 10, 5);
|
||||
break;
|
||||
case SLEEP_TIME:
|
||||
OLED_DrawString("STME ", 5);
|
||||
OLED_DrawTwoNumber(systemSettings.SleepTime, 14 * 5);
|
||||
OLED_DrawString("SLTME ", 6);
|
||||
OLED_DrawTwoNumber(systemSettings.SleepTime, 6);
|
||||
break;
|
||||
case SHUTDOWN_TIME:
|
||||
OLED_DrawString("SHTME ", 6);
|
||||
OLED_DrawTwoNumber(systemSettings.ShutdownTime, 6);
|
||||
break;
|
||||
case MOTIONDETECT:/*Toggle the mode*/
|
||||
if (systemSettings.movementEnabled)
|
||||
OLED_DrawString("MOTN T", 7);
|
||||
OLED_DrawString("MOTION T", 8);
|
||||
else
|
||||
OLED_DrawString("MOTN F", 7);
|
||||
OLED_DrawString("MOTION F", 8);
|
||||
break;
|
||||
case TEMPDISPLAY:/*Are we showing in C or F ?*/
|
||||
if (systemSettings.displayTempInF)
|
||||
OLED_DrawString("TMPUNT F", 8);
|
||||
else
|
||||
OLED_DrawString("TMPUNT C", 8);
|
||||
break;
|
||||
|
||||
case LEFTY:
|
||||
|
||||
if (systemSettings.flipDisplay)
|
||||
OLED_DrawString("FLPDSP T", 8);
|
||||
else
|
||||
OLED_DrawString("FLPDSP F", 8);
|
||||
break;
|
||||
case MOTIONSENSITIVITY:
|
||||
switch (systemSettings.sensitivity) {
|
||||
case MOTION_HIGH:
|
||||
OLED_DrawString("SENSE H ", 8);
|
||||
break;
|
||||
case MOTION_MED:
|
||||
OLED_DrawString("SENSE M ", 8);
|
||||
break;
|
||||
case MOTION_LOW:
|
||||
OLED_DrawString("SENSE L ", 8);
|
||||
break;
|
||||
default:
|
||||
OLED_DrawString("SENSE ", 8);
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@@ -266,15 +404,59 @@ void DrawUI() {
|
||||
//The iron is in sleep temp mode
|
||||
//Draw in temp and sleep
|
||||
OLED_DrawString("SLP", 3);
|
||||
OLED_DrawThreeNumber(temp, 14 * 3);
|
||||
drawTemp(temp, 4);
|
||||
|
||||
if (millis() - getLastMovement() > (10 * 60 * 1000)
|
||||
&& (millis() - getLastButtonPress() > (10 * 60 * 1000))) {
|
||||
//OLED off
|
||||
Oled_DisplayOff();
|
||||
} else {
|
||||
Oled_DisplayOn();
|
||||
}
|
||||
|
||||
break;
|
||||
case COOLING:
|
||||
//We are warning the user the tip is cooling
|
||||
OLED_DrawString("COL", 3);
|
||||
OLED_DrawThreeNumber(temp, 14 * 3);
|
||||
OLED_DrawString("COOL ", 5);
|
||||
drawTemp(temp, 5);
|
||||
break;
|
||||
case UVLOWARN:
|
||||
OLED_DrawString("UND VL", 6);
|
||||
OLED_DrawString("LOW VOLT", 8);
|
||||
break;
|
||||
case THERMOMETER:
|
||||
temp = readIronTemp(0, 1, 0xFFFF); //Force a reading as heater is off
|
||||
OLED_DrawString("TEMP ", 5);//extra one to it clears the leftover 'L' from IDLE
|
||||
drawTemp(temp, 5);
|
||||
break;
|
||||
case DCINDISP: {
|
||||
uint16_t voltage = readDCVoltage(systemSettings.voltageDiv); //get X10 voltage
|
||||
|
||||
if (CalStatus == 0 || ((millis() % 1000) > 500)) {
|
||||
OLED_DrawString("IN", 2);
|
||||
OLED_DrawChar((voltage / 100) % 10, 2);
|
||||
voltage -= (voltage / 100) * 100;
|
||||
OLED_DrawChar((voltage / 10) % 10, 3);
|
||||
voltage -= (voltage / 10) * 10;
|
||||
OLED_DrawChar('.', 4);
|
||||
OLED_DrawChar(voltage % 10, 5);
|
||||
OLED_DrawChar('V', 6);
|
||||
OLED_DrawChar(' ', 7);
|
||||
} else {
|
||||
OLED_DrawString("IN ", 8);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TEMPCAL: {
|
||||
|
||||
if (CalStatus == 0) {
|
||||
OLED_DrawString("CAL TEMP", 8);
|
||||
} else if (CalStatus == 1) {
|
||||
OLED_DrawString("CAL OK ", 8);
|
||||
} else if (CalStatus == 2) {
|
||||
OLED_DrawString("CAL FAIL", 8);
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
|
||||
@@ -13,44 +13,76 @@
|
||||
#include "I2C.h"
|
||||
|
||||
#include "Font.h"
|
||||
int8_t displayOffset = 32;
|
||||
/*Setup params for the OLED screen*/
|
||||
u8 OLED_Setup_Array[46] = { 0x80, 0xAE, 0x80, 0xD5, 0x80, 0x52, 0x80, 0xA8,
|
||||
0x80, 0x0f, 0x80, 0xC0, 0x80, 0xD3, 0x80, 0x00, 0x80, 0x40, 0x80, 0xA0,
|
||||
0x80, 0x8D, 0x80, 0x14, 0x80, 0xDA, 0x80, 0x02, 0x80, 0x81, 0x80, 0x33,
|
||||
0x80, 0xD9, 0x80, 0xF1, 0x80, 0xDB, 0x80, 0x30, 0x80, 0xA4, 0x80, 0XA6,
|
||||
0x80, 0xAF };
|
||||
/*http://www.displayfuture.com/Display/datasheet/controller/SSD1307.pdf*/
|
||||
/*All commands are prefixed with 0x80*/
|
||||
u8 OLED_Setup_Array[46] = { 0x80, 0xAE,/*Display off*/
|
||||
0x80, 0xD5,/*Set display clock divide ratio / osc freq*/
|
||||
0x80, 0x52,/*Unknown*/
|
||||
0x80, 0xA8,/*Set Multiplex Ratio*/
|
||||
0x80, 0x0F, /*16 == max brightness,39==dimmest*/
|
||||
0x80, 0xC0,/*Set COM Scan direction*/
|
||||
0x80, 0xD3,/*Set Display offset*/
|
||||
0x80, 0x00,/*0 Offset*/
|
||||
0x80, 0x40,/*Set Display start line to 0*/
|
||||
0x80, 0xA0,/*Set Segment remap to normal*/
|
||||
0x80, 0x8D,/*Unknown*/
|
||||
0x80, 0x14,/*Unknown*/
|
||||
0x80, 0xDA,/*Set VCOM Pins hardware config*/
|
||||
0x80, 0x02,/*Combination 2*/
|
||||
0x80, 0x81,/*Contrast*/
|
||||
0x80, 0x33,/*51*/
|
||||
0x80, 0xD9,/*Set pre-charge period*/
|
||||
0x80, 0xF1,/**/
|
||||
0x80, 0xDB,/*Adjust VCOMH regulator ouput*/
|
||||
0x80, 0x30,/*Unknown*/
|
||||
0x80, 0xA4,/*Enable the display GDDR*/
|
||||
0x80, 0XA6,/*Normal display*/
|
||||
0x80, 0xAF /*Dispaly on*/
|
||||
};
|
||||
|
||||
/*******************************************************************************
|
||||
/*
|
||||
Function: Oled_DisplayOn
|
||||
Description:Turn on the Oled display
|
||||
*******************************************************************************/
|
||||
*/
|
||||
void Oled_DisplayOn(void) {
|
||||
u8 data[6] = { 0x80, 0X8D, 0x80, 0X14, 0x80, 0XAF };
|
||||
|
||||
I2C_PageWrite(data, 6, DEVICEADDR_OLED);
|
||||
}
|
||||
/*******************************************************************************
|
||||
/*
|
||||
Function: Oled_DisplayOff
|
||||
Description:Turn off the Oled display
|
||||
*******************************************************************************/
|
||||
*/
|
||||
void Oled_DisplayOff(void) {
|
||||
u8 data[6] = { 0x80, 0X8D, 0x80, 0X10, 0x80, 0XAE };
|
||||
|
||||
I2C_PageWrite(data, 6, DEVICEADDR_OLED);
|
||||
}
|
||||
/*
|
||||
* This sets the OLED screen to invert the screen (flip it vertically)
|
||||
* This is used if the unit is set to left hand mode
|
||||
*/
|
||||
void Oled_DisplayFlip() {
|
||||
u8 data[2] = { 0x80, 0XC8 };
|
||||
I2C_PageWrite(data, 2, DEVICEADDR_OLED);
|
||||
data[1] = 0xA1;
|
||||
I2C_PageWrite(data, 2, DEVICEADDR_OLED);
|
||||
displayOffset = 0;
|
||||
|
||||
/*******************************************************************************
|
||||
Function: Data_Command
|
||||
}
|
||||
/*
|
||||
Description: write a command to the Oled display
|
||||
Input: number of bytes to write, array to write
|
||||
Output:
|
||||
*******************************************************************************/
|
||||
*/
|
||||
u8* Data_Command(u8 length, u8* data) {
|
||||
int i;
|
||||
u8 tx_data[128];
|
||||
u8 tx_data[129];
|
||||
//here are are inserting the data write command at the beginning
|
||||
tx_data[0] = 0x40;
|
||||
length += 1;
|
||||
length++;
|
||||
for (i = 1; i < length; i++) //Loop through the array of data
|
||||
tx_data[i] = *data++;
|
||||
I2C_PageWrite(tx_data, length, DEVICEADDR_OLED); //write out the buffer
|
||||
@@ -62,8 +94,9 @@ u8* Data_Command(u8 length, u8* data) {
|
||||
Input:x,y co-ordinates
|
||||
*******************************************************************************/
|
||||
void Set_ShowPos(u8 x, u8 y) {
|
||||
u8 pos_param[8] = { 0x80, 0xB0, 0x80, 0x21, 0x80, 0x20, 0x80, 0x7F };
|
||||
pos_param[5] = x + 32;
|
||||
u8 pos_param[8] = { 0x80, 0xB0, 0x80, 0x21, 0x80, 0x00, 0x80, 0x7F };
|
||||
//page 0, start add = x(below) through to 0x7F (aka 127)
|
||||
pos_param[5] = x + displayOffset;/*Display offset ==0 for Lefty, == 32 for righty*/
|
||||
pos_param[1] += y;
|
||||
I2C_PageWrite(pos_param, 8, DEVICEADDR_OLED);
|
||||
}
|
||||
@@ -72,7 +105,7 @@ void Set_ShowPos(u8 x, u8 y) {
|
||||
Function:Oled_DrawArea
|
||||
Description:
|
||||
Inputs:(x,y) start point, (width,height) of enclosing rect, pointer to data
|
||||
Output: last byte written out
|
||||
Output: pointer to the last byte written out
|
||||
*******************************************************************************/
|
||||
u8* Oled_DrawArea(u8 x0, u8 y0, u8 wide, u8 high, u8* ptr) {
|
||||
u8 m, n, y;
|
||||
@@ -109,16 +142,21 @@ void GPIO_Init_OLED(void) {
|
||||
}
|
||||
/*******************************************************************************
|
||||
Function: Init_Oled
|
||||
Description: Initalizes the Oled screen
|
||||
Description: Initializes the Oled screen
|
||||
*******************************************************************************/
|
||||
void Init_Oled(void) {
|
||||
void Init_Oled(uint8_t leftHanded) {
|
||||
u8 param_len;
|
||||
|
||||
OLED_RST();
|
||||
delayMs(2);
|
||||
delayMs(5);
|
||||
OLED_ACT(); //Toggling reset to reset the oled
|
||||
delayMs(2);
|
||||
delayMs(5);
|
||||
param_len = 46;
|
||||
if (leftHanded) {
|
||||
OLED_Setup_Array[11] = 0xC8;
|
||||
OLED_Setup_Array[19] = 0xA1;
|
||||
displayOffset = 0;
|
||||
}
|
||||
I2C_PageWrite((u8 *) OLED_Setup_Array, param_len, DEVICEADDR_OLED);
|
||||
}
|
||||
|
||||
@@ -128,56 +166,103 @@ void Init_Oled(void) {
|
||||
*******************************************************************************/
|
||||
void Clear_Screen(void) {
|
||||
u8 tx_data[128];
|
||||
memset(&tx_data[0], 0, 128);
|
||||
memset(tx_data, 0, 128);
|
||||
for (u8 i = 0; i < 2; i++) {
|
||||
Oled_DrawArea(0, i * 8, 128, 8, tx_data);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Draws a string onto the screen starting at the left
|
||||
*/
|
||||
void OLED_DrawString(char* string, uint8_t length) {
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
OLED_DrawChar(string[i], i * 14);
|
||||
OLED_DrawChar(string[i], i);
|
||||
}
|
||||
}
|
||||
void OLED_DrawChar(char c, uint8_t x) {
|
||||
if ((x) > (128 - 14))
|
||||
return; //Rudimentary clipping to not draw off screen
|
||||
u8* ptr;
|
||||
ptr = (u8*) FONT;
|
||||
if (c >= 'A' && c <= 'Z') {
|
||||
ptr += (c - 'A' + 10) * (14 * 2); //alpha is ofset 10 chars into the array
|
||||
} else if (c >= '0' && c <= '9')
|
||||
ptr += (c - '0') * (14 * 2);
|
||||
else if (c < 10)
|
||||
ptr += (c) * (14 * 2);
|
||||
else if (c == ' ') {
|
||||
//blank on space bar
|
||||
ptr += (36) * (14 * 2);
|
||||
} else if (c == '<') {
|
||||
ptr += (37) * (14 * 2);
|
||||
} else if (c == '>') {
|
||||
ptr += (38) * (14 * 2);
|
||||
}
|
||||
|
||||
Oled_DrawArea(x, 0, 14, 16, (u8*) ptr);
|
||||
}
|
||||
/*
|
||||
* Draw a 2 digit number to the display
|
||||
* */
|
||||
void OLED_DrawTwoNumber(uint8_t in, uint8_t x) {
|
||||
OLED_DrawChar((in / 10) % 10, x);
|
||||
OLED_DrawChar(in % 10, x + 14);
|
||||
* Draw a char onscreen at letter index x
|
||||
*/
|
||||
void OLED_DrawChar(char c, uint8_t x) {
|
||||
if (x > 7)
|
||||
return; //clipping
|
||||
x *= FONT_WIDTH; //convert to a x coordinate
|
||||
|
||||
u8* ptr = (u8*) FONT;
|
||||
if (c >= 'A' && c <= 'Z') {
|
||||
ptr += (c - 'A' + 10) * (FONT_WIDTH * 2); //alpha is ofset 10 chars into the array
|
||||
} else if (c >= '0' && c <= '9')
|
||||
ptr += (c - '0') * (FONT_WIDTH * 2);
|
||||
else if (c < 10)
|
||||
ptr += (c) * (FONT_WIDTH * 2);
|
||||
else if (c == ' ') {
|
||||
//blank on space bar
|
||||
ptr += (36) * (FONT_WIDTH * 2);
|
||||
} else if (c == '<') {
|
||||
ptr += (37) * (FONT_WIDTH * 2);
|
||||
} else if (c == '>') {
|
||||
ptr += (38) * (FONT_WIDTH * 2);
|
||||
} else if (c == '.') {
|
||||
ptr += (39) * (FONT_WIDTH * 2);
|
||||
}
|
||||
|
||||
Oled_DrawArea(x, 0, FONT_WIDTH, 16, (u8*) ptr);
|
||||
}
|
||||
|
||||
void OLED_BlankSlot(uint8_t xStart, uint8_t width) {
|
||||
u8* ptr = (u8*) FONT;
|
||||
ptr += (36) * (FONT_WIDTH * 2);
|
||||
|
||||
Oled_DrawArea(xStart, 0, width, 16, (u8*) ptr);
|
||||
}
|
||||
|
||||
/*
|
||||
* Draw a 2 digit number to the display at letter slot x
|
||||
*/
|
||||
void OLED_DrawTwoNumber(uint8_t in, uint8_t x) {
|
||||
|
||||
OLED_DrawChar((in / 10) % 10, x);
|
||||
OLED_DrawChar(in % 10, x + 1);
|
||||
}
|
||||
/*
|
||||
* Draw a 3 digit number to the display at letter slot x
|
||||
*/
|
||||
void OLED_DrawThreeNumber(uint16_t in, uint8_t x) {
|
||||
|
||||
OLED_DrawChar((in / 100) % 10, x);
|
||||
OLED_DrawChar((in / 10) % 10, x + 14);
|
||||
OLED_DrawChar(in % 10, x + 28);
|
||||
OLED_DrawChar((in / 10) % 10, x + 1);
|
||||
OLED_DrawChar(in % 10, x + 2);
|
||||
}
|
||||
/*
|
||||
* Draw a 4 digit number to the display at letter slot x
|
||||
*/
|
||||
void OLED_DrawFourNumber(uint16_t in, uint8_t x) {
|
||||
|
||||
OLED_DrawChar((in / 1000) % 10, x);
|
||||
OLED_DrawChar((in / 100) % 10, x + 14);
|
||||
OLED_DrawChar((in / 10) % 10, x + 28);
|
||||
OLED_DrawChar(in % 10, x + 42);
|
||||
OLED_DrawChar((in / 100) % 10, x + 1);
|
||||
OLED_DrawChar((in / 10) % 10, x + 2);
|
||||
OLED_DrawChar(in % 10, x + 3);
|
||||
}
|
||||
|
||||
void OLED_DrawIDLELogo() {
|
||||
static uint8_t drawAttempt = 0;
|
||||
drawAttempt++;
|
||||
if (drawAttempt & 0x80) {
|
||||
if (drawAttempt & 0x08)
|
||||
Oled_DrawArea(0, 0, 96, 8, (u8*) Iron_RightArrow_UP);
|
||||
else
|
||||
Oled_DrawArea(0, 0, 96, 8, (u8*) Iron_RightArrow_DOWN);
|
||||
|
||||
Oled_DrawArea(0, 8, 96, 8, (u8*) Iron_Base);
|
||||
} else {
|
||||
if (drawAttempt & 0x08)
|
||||
Oled_DrawArea(0, 0, 96, 8, (u8*) Iron_LeftArrow_UP);
|
||||
else
|
||||
Oled_DrawArea(0, 0, 96, 8, (u8*) Iron_LeftArrow_DOWN);
|
||||
Oled_DrawArea(0, 8, 96, 8, (u8*) Iron_Base);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void OLED_DrawSymbol(uint8_t x, uint8_t symbol) {
|
||||
Oled_DrawArea(x * FONT_WIDTH, 0, 16, 16, SymbolTable + (symbol * 32));
|
||||
}
|
||||
|
||||
@@ -12,7 +12,7 @@
|
||||
int32_t computePID(uint16_t setpoint) {
|
||||
int32_t ITerm = 0;
|
||||
static int16_t lastReading = 0;
|
||||
uint16_t currentReading = readIronTemp(0, 1); //get the current temp of the iron
|
||||
uint16_t currentReading = readIronTemp(0, 1,setpoint); //get the current temp of the iron
|
||||
int16_t error = (int16_t) setpoint - (int16_t) currentReading; //calculate the error term
|
||||
ITerm += (pidSettings.ki * error);
|
||||
if (ITerm > MAXPIDOUTPUT)
|
||||
@@ -34,7 +34,7 @@ int32_t computePID(uint16_t setpoint) {
|
||||
}
|
||||
/*Sets up the pid values*/
|
||||
void setupPID(void) {
|
||||
pidSettings.kp = 22;
|
||||
pidSettings.kp = 25;
|
||||
pidSettings.ki = 7;
|
||||
pidSettings.kd = 2;
|
||||
|
||||
|
||||
@@ -8,9 +8,9 @@
|
||||
*/
|
||||
|
||||
#include "Settings.h"
|
||||
#define FLASH_ADDR (0x8000000|48896)
|
||||
#define FLASH_ADDR (0x8000000|48896)/*Flash start OR'ed with the maximum amount of flash - 256 bytes*/
|
||||
void saveSettings() {
|
||||
//First we erase the flash
|
||||
//First we erase the flash
|
||||
FLASH_Unlock(); //unlock flash writing
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
|
||||
while (FLASH_ErasePage(FLASH_ADDR) != FLASH_COMPLETE)
|
||||
@@ -26,9 +26,8 @@ void saveSettings() {
|
||||
void restoreSettings() {
|
||||
//We read the flash
|
||||
uint16_t *data = (uint16_t*) &systemSettings;
|
||||
for(uint8_t i=0;i<(sizeof(systemSettings)/2);i++)
|
||||
{
|
||||
data[i] = *(uint16_t *)(FLASH_ADDR + (i*2));
|
||||
for (uint8_t i = 0; i < (sizeof(systemSettings) / 2); i++) {
|
||||
data[i] = *(uint16_t *) (FLASH_ADDR + (i * 2));
|
||||
}
|
||||
//if the version is correct were done
|
||||
//if not we reset and save
|
||||
@@ -42,11 +41,17 @@ void restoreSettings() {
|
||||
|
||||
void resetSettings() {
|
||||
|
||||
systemSettings.SleepTemp = 900;
|
||||
systemSettings.SleepTime = 1;
|
||||
systemSettings.SolderingTemp = 3200;
|
||||
systemSettings.movementEnabled = 1; //we use movement detection
|
||||
systemSettings.cutoutVoltage = 9;
|
||||
systemSettings.version=SETTINGSVERSION;
|
||||
systemSettings.SleepTemp = 1500; //Temperature the iron sleeps at - default 150.0 C
|
||||
systemSettings.SleepTime = 1; //How many minutes we wait until going to sleep - default 1 min
|
||||
systemSettings.SolderingTemp = 3200; //Default soldering temp is 320.0 C
|
||||
systemSettings.movementEnabled = 1; //we use movement detection by default
|
||||
systemSettings.cutoutVoltage = 10; //10V is the minium cutout voltage as the unit V measurement is unstable below 9.5V
|
||||
systemSettings.version = SETTINGSVERSION; //Store the version number to allow for easier upgrades
|
||||
systemSettings.displayTempInF =0; //default to C
|
||||
systemSettings.flipDisplay=0; //Default to right handed mode
|
||||
systemSettings.sensitivity=0x00; //Default high sensitivity
|
||||
systemSettings.tempCalibration=239; //Default to their calibration value
|
||||
systemSettings.voltageDiv=144; //Default divider from schematic
|
||||
systemSettings.ShutdownTime=30;
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user