Moved to use EXTI to read button status

Temperature sensor appears to work (may need calibration work still)
This commit is contained in:
Ben V. Brown
2016-09-20 23:11:36 +10:00
parent 98ca6784a0
commit 52e92feae7
20 changed files with 321 additions and 2035 deletions

View File

@@ -8,6 +8,9 @@
#ifndef ANALOG_H_
#define ANALOG_H_
#include "stm32f10x.h"
#include "S100V0_1.h"
#include "Bios.h"
extern volatile uint16_t ADC1ConvertedValue[2];
uint16_t Get_ADC1Value(uint8_t i);
uint16_t readIronTemp(uint16_t calibration);

View File

@@ -1,33 +1,25 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. ********************
File Name : Bios.h
Version : S100 APP Ver 2.11
Description:
Author : bure & Celery
Data: 2015/08/03
History:
2015/08/03 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
*******************************************************************************/
File Name : Bios.h
Version : S100 APP Ver 2.11
Description:
Author : bure & Celery
Data: 2015/08/03
History:
2015/08/03 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
*******************************************************************************/
#ifndef __BIOS_H
#define __BIOS_H
#include "stm32f10x.h"
#include "S100V0_1.h"
#include "Analog.h"
extern volatile u32 gTime[];
extern volatile uint32_t gHeat_cnt;
inline void setIronTimer(uint32_t time) {
gHeat_cnt = time;
}
#define USB_DN_OUT() GPIOA->CRH = (GPIOA->CRH & 0xFFFF3FFF) | 0x00003000
#define USB_DP_OUT() GPIOA->CRH = (GPIOA->CRH & 0xFFF3FFFF) | 0x00030000
#define USB_DN_EN() GPIOA->CRH = (GPIOA->CRH & 0xFFFFBFFF) | 0x0000B000
#define USB_DP_EN() GPIOA->CRH = (GPIOA->CRH & 0xFFFBFFFF) | 0x000B0000
#define USB_DP_PD() GPIOA->CRH = (GPIOA->CRH & 0xFFF3FFFF) | 0x00030000
#define USB_DN_HIGH() GPIOA->BSRR = GPIO_Pin_11
#define USB_DP_HIGH() GPIOA->BSRR = GPIO_Pin_12
#define USB_DN_LOW() GPIOA->BRR = GPIO_Pin_11
#define USB_DP_LOW() GPIOA->BRR = GPIO_Pin_12
#define LOW 0
#define HIGH 1
@@ -35,7 +27,6 @@ extern volatile u32 gTime[];
#define BLINK 1 // Bit0 : 0/1 <20><>ʾ/<2F><>˸״̬<D7B4><CCAC>־
#define WAIT_TIMES 100000
#define SECTOR_SIZE 512
#define SECTOR_CNT 4096
#define HEAT_T 200

View File

@@ -1,71 +0,0 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. **********************
File Name : CTRL.h
Version : S100 APP Ver 2.11
Description:
Author : Celery
Data: 2015/07/07
History:
2015/07/07 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
*******************************************************************************/
#ifndef _CTRL_H
#define _CTRL_H
#include "stm32f10x.h"
#include "Bios.h"
#define TEMPSHOW_TIMER gTime[0]/*TEMPSHOW_TIMER*/
#define HEATING_TIMER gTime[1]/*HEATING_TIMER*/
#define ENTER_WAIT_TIMER gTime[2]/*ENTER_WAIT_TIMER*/
#define EFFECTIVE_KEY_TIMER gTime[3]/*EFFECTIVE_KEY_TIMER*/
#define LEAVE_WAIT_TIMER gTime[4]/*LEAVE_WAIT_TIMER*/
#define G6_TIMER gTime[5]/*SWITCH_SHOW_TIMER*/
#define UI_TIMER gTime[6]/*UI_TIMER */
#define KD_TIMER gTime[7]/**/
///^^-- All the times in gTime are decremented by 1 if >0 by timer2 tick <bottom of bios.c>
//------------------------------ ------------------------------------//
#define KEY_ST(KEY_PIN) GPIO_ReadInputDataBit(GPIOA, KEY_PIN)
#define NO_KEY 0x0 /*NO Keys pressed*/
#define KEY_A 0x0100/*V1 key pressed*/
#define KEY_B 0x0040/*V2 Key pressed*/
#define KEY_CN 0X8000/*(Long key press)*/
#define KEY_V3 (KEY_A|KEY_B)/*Both Keys pressed*/
typedef enum WORK_STATUS {
IDLE = 1, //System is idle
THERMOMETER, //Thermometer mode, basically reads sensor and shows temp
SOLDERING_MODE, //Soldering Mode (Temp Controlled)
WAIT, //System in wait state
TEMP_SET, //Setting the soldering temp
SETTINGS_MENU, // Show the user the settings menu
USB_POWER, //USB Powered Mode
MODE_CNG, //DFU mode i think??
ALARM, //An alarm has been fired
} WORK_STATUS;
typedef enum WARNING_STATUS {
NORMAL_TEMP = 1, HIGH_TEMP, SEN_ERR, HIGH_VOLTAGE, LOW_VOLTAGE,
} WARNING_STATUS;
typedef struct {
u8 ver[16];
s16 t_standby; // 200<30><30>C=1800 2520,<2C><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
s16 t_work; // 350<35><30>C=3362, <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
s16 t_step; //<2F><><EFBFBD>ò<EFBFBD><C3B2><EFBFBD>
u32 wait_time; //3*60*100 3 mintute
u32 idle_time; //6*60*100 6 minute
} DEVICE_INFO_SYS;
extern DEVICE_INFO_SYS device_info;
void Set_PrevTemp(s16 Temp);
u8 Get_CtrlStatus(void);
void Set_CtrlStatus(u8 status);
s16 Get_TempVal(void);
u16 Get_HtFlag(void);
void System_Init(void);
void Pid_Init(void);
u16 Pid_Realize(s16 temp);
u32 Heating_Time(s16 temp, s16 wk_temp);
void Status_Tran(void);
#endif
/******************************** END OF FILE *********************************/

View File

@@ -81,6 +81,8 @@ const u8 FONT[]={
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,/* */
};

View File

@@ -1,49 +0,0 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. **********************
File Name : CTRL.h
Version : S100 APP Ver 2.11
Description:
Author : Celery
Data: 2015/07/07
History:
2015/07/07 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
*******************************************************************************/
#ifndef _HARDWARE_H
#define _HARDWARE_H
#include "stm32f10x.h"
#define SI_COE 8//56
#define SI_THRESHOLD 60
typedef enum VOL_CLASS {
H_ALARM = 0,
VOL_24,
VOL_19,
VOL_12,
VOL_5,
L_ALARM,
} VOL_CLASS;
extern s32 gZerop_ad;
extern u8 gCalib_flag;
extern u32 gTurn_offv;
u32 Get_gKey(void);
void Set_gKey(u32 key);
void Set_LongKeyFlag(u32 flag);
void Zero_Calibration(void);
int Read_Vb(u8 flag);
void Scan_Key(void);
u32 Get_SlAvg(u32 avg_data);
int Get_TempSlAvg(int avg_data);
u32 Get_AvgAd(void);
int Get_SensorTmp(void);
u16 Get_ThermometerTemp(void);
s16 Get_Temp(s16 wk_temp);
void Clear_Watchdog(void);
u32 Start_Watchdog(u32 ms);
u8 Get_AlarmType(void);
void Set_AlarmType(u8 type);
u32 Get_CalFlag(void);
#endif
/******************************** END OF FILE *********************************/

View File

@@ -30,10 +30,25 @@ void TIM2_IRQHandler(void);
void TIM3_IRQHandler(void);
extern volatile uint32_t system_Ticks;
void delayMs(uint32_t ticks);
volatile extern uint32_t lastKeyPress;
volatile extern uint32_t lastMovement;
volatile extern uint16_t keyState;
inline uint32_t millis() {
return system_Ticks;
}
inline uint32_t getLastButtonPress() {
return lastKeyPress;
}
inline uint32_t getLastMovement(){
return lastMovement;
}
inline uint16_t getButtons() {
return keyState;
}
void WWDG_IRQHandler(void);
void PVD_IRQHandler(void);

View File

@@ -7,12 +7,10 @@
#ifndef MODES_H_
#define MODES_H_
#include "CTRL.h"
#include "Hardware.h"
#include "Interrupt.h"
#include "S100V0_1.h"
#include "Oled.h"
uint32_t LastButtonPushTime;
uint32_t LastMovementTime;
enum {
STARTUP, //we are sitting on the prompt to push a button
SOLDERING,
@@ -25,10 +23,15 @@ enum {
UVLO = 0, SLEEP_TEMP, SLEEP_TIME,
} settingsPage;
struct {
uint32_t SolderingTemp; //current setpoint for the iron
uint8_t SleepTime; //minutes to sleep
uint32_t SleepTemp; //temp to drop to in sleep
uint8_t cutoutVoltage; //X10 the voltage we cutout at for undervoltage
uint8_t movementEnabled;
} systemSettings;
void ProcessUI();
void DrawUI();
#endif /* MODES_H_ */

View File

@@ -12,6 +12,7 @@
#define DEVICEADDR_OLED 0x3c
#include "stm32f10x.h"
#include "Interrupt.h"
void Sc_Pt(u8 Co);
void Oled_DisplayOn(void);
void Oled_DisplayOff(void);
@@ -32,6 +33,7 @@ void Display_BG(void);
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_DrawThreeNumber(uint16_t in, uint8_t x);
#endif
/******************************** END OF FILE *********************************/

View File

@@ -8,15 +8,19 @@
#define MCU_TYPE "STM32F103T8"
#define SCH_VER "2.46"
#define SPIx SPI1
//--------------------------- key Definitions ------------------------------//
#define KEY1_PIN GPIO_Pin_9 //PA8
#define KEY2_PIN GPIO_Pin_6 //PA6
#define KEY_A KEY1_PIN
#define KEY_B KEY2_PIN
#define BUT_A 0x01
#define BUT_B 0x02
#define BUT_AB BUT_A|BUT_B
#define KEY_1 !(GPIOA->IDR & KEY1_PIN)
#define KEY_2 !(GPIOA->IDR & KEY2_PIN)
#define KEY_DFU KEY_1
#define KEY_ON 0
#define I2C1_DMA_CHANNEL_TX DMA1_Channel6
#define I2C1_DMA_CHANNEL_RX DMA1_Channel7
@@ -27,7 +31,6 @@
#define I2C1_DR_Address 0x40005410
#define I2C2_DR_Address 0x40005810
//--------------------------- OLED ------------------------------//
#define OLED_RST_PIN GPIO_Pin_8 //PA9
#define OLED_RST() GPIO_ResetBits(GPIOA, OLED_RST_PIN)

View File

@@ -1,46 +0,0 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. **********************
File Name : UI.h
Version : S100 APP Ver 2.11
Description:
Author : Celery
Data: 2015/07/07
History:
2015/07/07 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
*******************************************************************************/
#ifndef _UI_H
#define _UI_H
#include "stm32f10x.h"
u32 Get_UpdataFlag(void);
void Set_UpdataFlag(u32 Cont);
void APP_Init(void);
u32 Calculation_TWork(u8 Flag);
void Temp_SetProc(void);
void Display_Temp(u8 x, s16 Temp);
void Show_Notice(void);
void Show_Warning(void);
void Show_MiniTS(void);
void Show_TempDown(s16 Temp, s16 Dst_Temp);
void Set_TemperatureShowFlag(u8 flag);
s16 TemperatureShow_Change(u8 flag, s16 Tmp);
u8 Get_TemperatureShowFlag(void);
void Show_Triangle(u8 empty, u8 fill);
void Shift_Char(u8* ptr, u8 pos);
void Show_Set(void);
void Show_OrderChar(u8* ptr, u8 num, u8 width);
u8 Reverse_Bin8(u8 data);
void Show_ReverseChar(u8* ptr, u8 num, u8 width, u8 direction);
u8 Show_TempReverse(u8 num, u8 width, u8 direction);
void Show_HeatingIcon(u32 ht_flag, u16 active);
void Display_Str(u8 x, char* str);
void Display_Str10(u8 x, char* str);
void Clear_Pervious(u16 data);
void Print_Integer(s32 data, u8 posi);
u8 Roll_Num(u16 Step, u8 Flag);
void OLed_Display(void);
void Show_Cal(u8 flag);
void Show_Config(void);
#endif
/******************************** END OF FILE *********************************/

View File

@@ -32,7 +32,7 @@ int16_t readTipTemp() {
uint32_t max = 0, min;
uint32_t ad_value, avg_data;
Set_HeatingTime(0); //set the remaining time to zero
setIronTimer(0); //set the remaining time to zero
HEAT_OFF(); //heater must be off
delayMs(50); //wait for the heater to time out
uint8_t gMeas_cnt = 9; //how many measurements to make

View File

@@ -11,11 +11,10 @@
#include "APP_Version.h"
#include "Bios.h"
#include "I2C.h"
#include "CTRL.h"
#include <Hardware.h>
/******************************************************************************/
#define ADC1_DR_Address ((u32)0x4001244C)
vu32 gHeat_cnt = 0;
volatile uint32_t gHeat_cnt = 0;
/*******************************************************************************
Function:RCC_Config
@@ -48,7 +47,7 @@ void RCC_Config(void) {
RCC_ClocksTypeDef RCC_Clocks;
RCC_GetClocksFreq(&RCC_Clocks);
SysTick_Config(RCC_Clocks.HCLK_Frequency / 1000);//Enable the systick timer
SysTick_Config(RCC_Clocks.HCLK_Frequency / 1000); //Enable the systick timer
}
/*******************************************************************************
Function: NVIC_Config
@@ -253,6 +252,57 @@ void Init_Timer3(void) {
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
//We want to enable the EXTI IRQ for the two buttons on PA6 and PA9
void Init_EXTI(void) {
EXTI_InitTypeDef EXTI_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
GPIO_EXTILineConfig(GPIO_PortSourceGPIOA,
GPIO_PinSource6 | GPIO_PinSource9);
/* Configure EXTI0 line */
EXTI_InitStructure.EXTI_Line = EXTI_Line6 | EXTI_Line9;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising_Falling; //trigger on up and down
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
/* Enable and set EXTI0 Interrupt to the lowest priority */
NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0F;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0F;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
/*******************************************************************************
Function:Start_Watchdog
Description: Starts the system watchdog timer
*******************************************************************************/
u32 Start_Watchdog(u32 ms) {
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
/* IWDG counter clock: 40KHz(LSI) / 32 = 1.25 KHz (min:0.8ms -- max:3276.8ms */
IWDG_SetPrescaler(IWDG_Prescaler_32);
/* Set counter reload value to XXms */
IWDG_SetReload(ms * 10 / 8);
/* Reload IWDG counter */
IWDG_ReloadCounter();
/* Enable IWDG (the LSI oscillator will be enabled by hardware) */
IWDG_Enable();
return 1;
}
/*******************************************************************************
Function:Clear_Watchdog
Description:Resets the watchdog timer
*******************************************************************************/
void Clear_Watchdog(void) {
IWDG_ReloadCounter();
}
/*******************************************************************************
Function:TIM2_ISR
Description:Handles Timer 2 tick. (10mS)
@@ -260,15 +310,9 @@ void Init_Timer3(void) {
Also reads the buttons every 4 ticks
*******************************************************************************/
void TIM2_ISR(void) {
volatile static u8 buttonReadDivider;
TIM_ClearITPendingBit(TIM2, TIM_IT_Update); // Clear interrupt flag
for (u8 i = 0; i < 8; i++)
if (gTime[i] > 0)
gTime[i]--;
if (++buttonReadDivider % 4 == 0)
Scan_Key();
}
/*******************************************************************************
Function: TIM3_ISR
@@ -280,11 +324,6 @@ void TIM3_ISR(void) {
TIM_ClearITPendingBit(TIM3, TIM_IT_Update); // Clear interrupt flag
if (gTimeOut > 0)
gTimeOut--;
if (gMs_timeout > 0)
gMs_timeout--;
if (gHeat_cnt > 0) {
--gHeat_cnt;
if (heat_flag)

View File

@@ -1,441 +0,0 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. **********************
File Name : CTRL.c
Version : S100 APP Ver 2.11
Description:
Author : Celery
Data: 2015/08/03
History:
2015/07/07 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
2015/08/03 <20>Ż<EFBFBD><C5BB>ƶ<EFBFBD><C6B6>ж<EFBFBD>
*******************************************************************************/
#include <stdio.h>
#include <string.h>
#include "CTRL.h"
#include "Bios.h"
#include "UI.h"
#include "Hardware.h"
#include "S100V0_1.h"
#include "MMA8652FC.h"
#define HEATINGCYCLE 30
/******************************************************************************/
DEVICE_INFO_SYS device_info;
/******************************************************************************/
u8 gCtrl_status = 1;
//^ System current status / operating mode.
u16 gHt_flag = 0;
vs16 gTemp_data = 250; //
s16 gPrev_temp = 250; //
u8 gIs_restartkey = 0; //
u8 gPre_status = 1; //
const DEVICE_INFO_SYS info_def = { "2.13", //Ver
1000, //T_Standby; // 200C=1800 2520
1000, // T_Work; // 350C=3362,
100, //T_Step;
3 * 60 * 100, //Wait_Time; //3*60*100 3 minutes
6 * 60 * 100 // Idle_Time; //6*60*100 6 minutes
};
struct _pid {
s16 settemp; //Current ideal setpoint for the temp
s16 actualtemp; //Actual current temp of the tip
s16 err; //Error term
s16 err_last; //last error term
s32 ht_time; //
u16 kp, ki, kd; //Constants for the PID Controller
s32 integral; //
} pid;
/*******************************************************************************
Function: Get_Ctrl_Status
Description: Returns the current operating Mode
Input:Void
Output:Current System Status
*******************************************************************************/
u8 Get_CtrlStatus(void) {
return gCtrl_status;
}
/*******************************************************************************
Function: Set_CtrlStatus
Description: Set the current operating Mode
Input:status uint8_t
Output:Void
*******************************************************************************/
void Set_CtrlStatus(u8 status) {
gCtrl_status = status;
}
/*******************************************************************************
Function: Set_PrevTemp
Description:Set the previous temp record for the PID
Input:Previous Temp (int16_t)
Output:Void
*******************************************************************************/
void Set_PrevTemp(s16 temp) {
gPrev_temp = temp;
}
/*******************************************************************************
Function: Get_HtFlag
Description:
Input:Void
Output:Void
*******************************************************************************/
u16 Get_HtFlag(void) {
return gHt_flag;
}
/*******************************************************************************
Function:Get_TempVal
Description:
Input:Void
Output:Void
*******************************************************************************/
s16 Get_TempVal(void) {
return gTemp_data;
}
/*******************************************************************************
Function:System_Init
Description:Init the device info to be a known start value (as defined at top of CTRL.c)
Input:Void
Output:Void
*******************************************************************************/
void System_Init(void) {
memcpy((void*) &device_info, (void*) &info_def, sizeof(device_info));
}
/*******************************************************************************
Function:Pid_Init
Description:Inits the PID values to defaults (0 usually)
Input:Void
Output:Void
*******************************************************************************/
void Pid_Init(void) {
pid.settemp = 0;
pid.actualtemp = 0;
pid.err = 0;
pid.err_last = 0;
pid.integral = 0;
pid.ht_time = 0;
pid.kp = 15;
pid.ki = 2;
pid.kd = 1;
}
/*******************************************************************************
Function:Pid_Realize
Description: Calculates the next heating value using the PID algorithum
Input:Current temp from the tip
Output:
*******************************************************************************/
u16 Pid_Realize(s16 temp) {
u8 index = 0, index1 = 1;
s16 d_err = 0;
pid.actualtemp = temp;
pid.err = pid.settemp - pid.actualtemp; //
if (pid.err >= 500)//error is > 50 degrees
index = 0;
else {
index = 1;
pid.integral += pid.err; //
}
////////////////////////////////////////////////////////////////////////////////
//
if (pid.settemp < pid.actualtemp) {//cooling down
d_err = pid.actualtemp - pid.settemp;
if (d_err > 20) {
pid.integral = 0; //
index1 = 0;
index = 0;
}
}
////////////////////////////////////////////////////////////////////////////////
if (pid.err <= 30)
index1 = 0;
else
index1 = 1;
pid.ht_time = pid.kp * pid.err + pid.ki * index * pid.integral
+ pid.kd * (pid.err - pid.err_last) * index1;
pid.err_last = pid.err;
if (pid.ht_time <= 0)
pid.ht_time = 0;
else if (pid.ht_time > 30 * 200)
pid.ht_time = 30 * 200;
return pid.ht_time;
}
/*******************************************************************************
Function:Heating_Time
Description:Calcuates the on time for the heating element
Input: (temp) current Tip Temp, (wk_temp) current ideal setpoint temp
Output: The ON time for the heater element
*******************************************************************************/
u32 Heating_Time(s16 temp, s16 wk_temp) {
u32 heat_timecnt;
pid.settemp = wk_temp;
if (wk_temp > temp) {
if (wk_temp - temp >= 18)
gHt_flag = 0; //<2F><><EFBFBD><EFBFBD>
else
gHt_flag = 2; //<2F><><EFBFBD><EFBFBD>
} else {
if (temp - wk_temp <= 18)
gHt_flag = 2; //<2F><><EFBFBD><EFBFBD>
else
gHt_flag = 1; //<2F><><EFBFBD><EFBFBD>
}
heat_timecnt = Pid_Realize(temp); //Sub_data * 1000;
return heat_timecnt;
}
/*******************************************************************************
Function:Status_Tran
Description: Handles the current status of the unit, and task selection
Basically this is called in main() repeatedly
Input:Void
Output:Void
*******************************************************************************/
void Status_Tran(void) //
{
static u16 init_waitingtime = 0;
static u8 back_prestatus = 0;
s16 heat_timecnt = 0, wk_temp;
u16 mma_active;
switch (Get_CtrlStatus()) {
case IDLE:
switch (Get_gKey()) { //Read current switch positions
case KEY_A: //If V1 key is pressed
if (gIs_restartkey != 1) { //check we are not in a soft restart situation
if (Read_Vb(1) < 4) { //Read that the input voltage is acceptable??
Set_CtrlStatus(SOLDERING_MODE); //Set to temperature controlled mode (Aka soldering mode)
init_waitingtime = 0; //Initialize the wait count to 0
TEMPSHOW_TIMER= 0; //Initialize the timer to 0
UI_TIMER= 0;
G6_TIMER= 0;
}
}
break;
case KEY_B: //check if V2 key is pressed
if(gIs_restartkey != 1) { //check this is not a soft restart situation
Set_CtrlStatus(THERMOMETER);//Change system to Thermometer mode instead (ie reading temp only, no drive)
UI_TIMER = 0;
Set_LongKeyFlag(1);//Set the long key pressed flag??
}
break;
case KEY_CN|KEY_V3: //If A&B pressed at the same time, no action
break;
}
if(gIs_restartkey && (KD_TIMER == 0)) { //This is a soft restart situation instead
gIs_restartkey = 0;//reset the flag for soft restart
Set_gKey(NO_KEY);//reset keys pressed
}
if(Read_Vb(1) == 0) { //Invalid voltage, I think this means no input power detected
if(Get_UpdataFlag() == 1) Set_UpdataFlag(0);
Set_CtrlStatus(ALARM);
}
if(gPre_status != WAIT && gPre_status != IDLE) { //System has been left alone, turn off screen to stop burn in
G6_TIMER = device_info.idle_time;
Set_gKey(NO_KEY);
gPre_status = IDLE;
}
break;
case SOLDERING_MODE: //We are in soldering mode
switch(Get_gKey()) { //switch on the pressed key
case KEY_CN|KEY_A:
case KEY_CN|KEY_B://if either key long pressed
Set_HeatingTime(0);//turn off heater
Set_CtrlStatus(TEMP_SET);//Goto temperature set mode
HEATING_TIMER = 0;//reset heating timer
EFFECTIVE_KEY_TIMER = 500;
break;
case KEY_CN|KEY_V3://Both keys pressed
Set_HeatingTime(0);//Stop the heater
Set_LongKeyFlag(0);//Reset the long key press flag
Set_CtrlStatus(IDLE);//Change the system back to IDLE state (stop soldering)
gPre_status = SOLDERING_MODE;//Set previous status
gIs_restartkey = 1;
KD_TIMER = 50;//
break;
}
if(Read_Vb(1) >= 4) { //Check input voltage is in the acceptable range
Set_HeatingTime(0);//Turn of heater as we are out of range
Set_LongKeyFlag(0);//reset key flag
Set_CtrlStatus(IDLE);//reset to IDLE state
gPre_status = SOLDERING_MODE;//set previous state
gIs_restartkey = 1;
KD_TIMER = 50;//
}
wk_temp = device_info.t_work; //update setpoint temp from the struct
if(HEATING_TIMER == 0) {
gTemp_data = Get_Temp(wk_temp);
heat_timecnt = Heating_Time(gTemp_data,wk_temp); //Calculate the on time for the heating cycle
Set_HeatingTime(heat_timecnt);//set the on time for the heating cycle
HEATING_TIMER = HEATINGCYCLE;
}
if(Get_HeatingTime() == 0) { //If calcuated heater time is 0 stop the timer ?
HEATING_TIMER = 0;
}
/*
* The logic here is :
* If the device is moving then disarm the timer and mark it as needed a re-init
* else check if the timer needs init, if it does set it up and exit
* if the timer does not need init, then check if the timer has expired (its a count down)
* If the timer has expired goto wait state instead and shutdown iron
*/
mma_active = Get_MmaShift(); //check the accelerometer for movement
if(mma_active == 0) { //MMA_active = 0 ==> static ,MMA_active = 1 ==>move
if(init_waitingtime == 0) { //If the waiting countdown timer is not initialized
init_waitingtime = 1;//we initialize it and set this <- flag.
ENTER_WAIT_TIMER = device_info.wait_time;
}
if((init_waitingtime != 0) && (ENTER_WAIT_TIMER == 0)) { //if timeout has been initalized and enter_wait_timer has reached 0
gHt_flag = 0;//reset heating flags
UI_TIMER = 0;//reset ui timers
Set_HeatingTime(0);//turn off the soldering iron
Set_gKey(0);//clear keys
G6_TIMER = device_info.idle_time;//set the device to idle timer move
Set_CtrlStatus(WAIT);//Set system mode to waiting for movement
}
} else { //The iron is moving
init_waitingtime = 0;//mark the waiting timer for needing reset if movement stops again
}
if(Get_AlarmType() > NORMAL_TEMP) { //
if(Get_UpdataFlag() == 1) Set_UpdataFlag(0);
Set_CtrlStatus(ALARM);//Change to alarm state
}
break;
case WAIT:
//This mode (WAIT) occures when the iron has been idling on a desk for too long (ie someone forgot it was left on)
//In this state we drop to a lower, safer temp and wait for movement or button push to wake up to operating temp again
wk_temp = device_info.t_standby;
if(device_info.t_standby > device_info.t_work) {
//Check if the set temp was greater than the idle temp, if it was we set the idle temp to the set temp
//This is done to avoid standby going to a higher temp
wk_temp = device_info.t_work;
}
//if the heating timer has expired, update the readings
if(HEATING_TIMER == 0) {
gTemp_data = Get_Temp(wk_temp); //read the tip temp
heat_timecnt = Heating_Time(gTemp_data,wk_temp);//calculate the new heating timer value from temps
Set_HeatingTime(heat_timecnt);//apply the new heating timer
HEATING_TIMER = 30;//set update rate for heating_timer
}
if(Read_Vb(1) >= 4) { //If the input voltage is not valid
Set_HeatingTime(0);//turn off heater
Set_LongKeyFlag(0);//reset key press flag
Set_CtrlStatus(IDLE);//goto IDLE state
G6_TIMER = device_info.idle_time;
gPre_status = WAIT;//set previous state
gIs_restartkey = 1;
KD_TIMER = 50;//
}
if(G6_TIMER == 0) { //
Set_HeatingTime(0);
Set_LongKeyFlag(0);
gIs_restartkey = 1;
KD_TIMER = 200;//
gPre_status = WAIT;
Set_CtrlStatus(IDLE);
}
//If movement has occurred OR a key has been pressed -> Wakeup back to soldering
mma_active = Get_MmaShift();//read accelerometer
if(mma_active == 1 || Get_gKey() != 0) {
UI_TIMER = 0; //reset the un-needed timers
G6_TIMER = 0;
init_waitingtime = 0;
Set_CtrlStatus(SOLDERING_MODE);//Go back to soldering iron mode
}
if(Get_AlarmType() > NORMAL_TEMP) { //If an alarm has occurred??
if(Get_UpdataFlag() == 1) Set_UpdataFlag(0);
Set_CtrlStatus(ALARM);//goto alarm error state
}
break;
case TEMP_SET: //We are in the setting soldering iron temp mode
if(EFFECTIVE_KEY_TIMER == 0) {
gCalib_flag = 1;
gCalib_flag = 0;
Set_CtrlStatus(SOLDERING_MODE); //return to soldering mode
TEMPSHOW_TIMER = 0;//turn off the timer
}
break;
case THERMOMETER: //we are measuring the tip temp without applying any power
if(KD_TIMER > 0) {
Set_gKey(NO_KEY);
break;
}
switch(Get_gKey()) {
case KEY_CN|KEY_A:
case KEY_CN|KEY_B:
back_prestatus = 1;
break;
case KEY_CN|KEY_V3:
Zero_Calibration(); //Calibrate the temperature (i think??)
if(Get_CalFlag() == 1) {
}
KD_TIMER = 200; //20150717 <20>޸<EFBFBD>
break;
default:
break;
}
if(back_prestatus == 1) { //we are exiting
back_prestatus = 0;//clear flag
Set_HeatingTime(0);//turn off heater? (not sure why this is done again)
Set_CtrlStatus(IDLE);//Goto IDLE state
gPre_status = THERMOMETER;//set previous state
gIs_restartkey = 1;//signal soft restart required as we may have done a calibration
Set_LongKeyFlag(0);//reset long key hold flag
KD_TIMER = 50;//
}
break;
case ALARM: //An error has occured so we are in alarm state
switch(Get_AlarmType()) {
case HIGH_TEMP: //over temp condition
case SEN_ERR://sensor reading error
wk_temp = device_info.t_work;
gTemp_data = Get_Temp(wk_temp);
if(Get_AlarmType() == NORMAL_TEMP) {
Set_CtrlStatus(SOLDERING_MODE);
Set_UpdataFlag(0);
}
break;
case HIGH_VOLTAGE: //over voltage
case LOW_VOLTAGE://under voltage
if(Read_Vb(1) >= 1 && Read_Vb(1) <= 3) {
Set_HeatingTime(0); //turn off heater
Set_LongKeyFlag(0);//reset key flag
gIs_restartkey = 1;
UI_TIMER = 2;// 2<><32>
gPre_status = THERMOMETER;
Set_CtrlStatus(IDLE);
}
break;
}
break;
default:
break;
}
}
/******************************** END OF FILE *********************************/

View File

@@ -1,225 +0,0 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. **********************
File Name : CTRL.c
Version : S100 APP Ver 2.11
Description:
Author : Celery
Data: 2015/07/07
History:
2015/07/07 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
2015/07/20 <20>Ӵ<EFBFBD><D3B4>¶ȱ<C2B6><C8B1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
*******************************************************************************/
#include <stdio.h>
#include <string.h>
#include "APP_Version.h"
#include "Hardware.h"
#include "CTRL.h"
#include "Bios.h"
#include "UI.h"
/******************************************************************************/
#define CAL_AD 250
const u32 gVol[] = { 3900, 2760, 1720, 584 };
const u16 gRate[] = { 300, 150, 90, 40 };
s32 gZerop_ad = 239;
u32 gTurn_offv = 100;
u8 gCalib_flag = 0;
vu16 gMeas_cnt = 0;/* Measure*/
u32 gKey_in;
u8 gLongkey_flag = 0;
u8 gAlarm_type = 1;
/*******************************************************************************
*******************************************************************************/
u32 Get_CalFlag(void) {
return gCalib_flag;
}
/*******************************************************************************
*******************************************************************************/
u32 Get_gKey(void) {
return gKey_in;
}
/*******************************************************************************
*******************************************************************************/
void Set_gKey(u32 key) {
gKey_in = key;
}
/*******************************************************************************
*******************************************************************************/
void Set_LongKeyFlag(u32 flag) {
gLongkey_flag = flag;
}
/*******************************************************************************
*******************************************************************************/
u8 Get_AlarmType(void) {
return gAlarm_type;
}
/*******************************************************************************
*******************************************************************************/
void Set_AlarmType(u8 type) {
gAlarm_type = type;
}
/*******************************************************************************
Function: Read_Vb
Description:Reads the input voltage and compares it to the thresholds??
Input:Selects which threshold we are comparing to
Output:Returns a key for if the voltage is in spec (I think)
*******************************************************************************/
int Read_Vb(u8 flag) {
u32 tmp, i, sum = 0;
for (i = 0; i < 10; i++) {
tmp = ADC_GetConversionValue(ADC2);
sum += tmp;
}
tmp = sum / 10;
if (tmp >= (gVol[0] + gVol[0] / 100)) {
gAlarm_type = HIGH_VOLTAGE;
return H_ALARM; //<2F><><EFBFBD><EFBFBD>3500
}
tmp = (tmp * 10 / 144); //<2F><>ѹvb = 3.3 * 85 *ad / 40950 -> In X10 voltage
for (i = 0; i < 4; i++) {
if (i == 2) {
if (flag == 0) {
if (tmp >= gRate[i])
break;
} else {
if (tmp >= gTurn_offv)
break;
}
} else {
if (tmp >= gRate[i])
break;
}
}
return (i + 1);
}
/*******************************************************************************
*******************************************************************************/
void Scan_Key(void) {
static u32 p_cnt = 0, key_statuslast = 0;
u32 key_state = 0;
if ((~GPIOA->IDR) & 0x0200)
key_state |= KEY_A; //KEY_V1
if ((~GPIOA->IDR) & 0x0040)
key_state |= KEY_B; //KEY_V2
if (key_state == 0)
return;
if (gLongkey_flag == 1) { //LongKey_flag -> we are looking for a long press or a quick press
if (key_statuslast == key_state) {
p_cnt++;
if (p_cnt > 21)
Set_gKey(KEY_CN | key_state);
} else {
p_cnt = 0;
key_statuslast = key_state;
Set_gKey(key_state);
}
} else {
p_cnt = 0;
key_statuslast = key_state;
Set_gKey(key_state);
}
}
/*******************************************************************************
Function:
Description: Reads the Zero Temp.. And does something..
*******************************************************************************/
void Zero_Calibration(void) {
u32 zerop;
int cool_tmp;
zerop = Get_AvgAd(); //get the current
cool_tmp = Get_SensorTmp(); //get the temp of the onboard sensor
if (zerop >= 400) { //If the tip is too hot abort
gCalib_flag = 2;
} else {
if (cool_tmp < 300) { //If cool temp is cool enough continue
gZerop_ad = zerop; //store the zero point
gCalib_flag = 1;
} else { //abort if too warm
gCalib_flag = 2;
}
}
}
/*******************************************************************************
*******************************************************************************/
s16 Get_Temp(s16 wk_temp) {
int ad_value, cool_tmp, compensation = 0;
static u16 cnt = 0, h_cnt = 0;
ad_value = Get_AvgAd();
cool_tmp = Get_SensorTmp();
if (ad_value == 4095)
h_cnt++;
else {
h_cnt = 0;
if (ad_value > 3800 && ad_value < 4095)
cnt++;
else
cnt = 0;
}
if (h_cnt >= 60 && cnt == 0)
gAlarm_type = SEN_ERR; //Sensor error -- too many invalid readings
if (h_cnt == 0 && cnt >= 10)
gAlarm_type = HIGH_TEMP; //Stuck at a really high temp -> Has mosfet failed
if (h_cnt < 60 && cnt < 10)
gAlarm_type = NORMAL_TEMP; //No errors so far
compensation = 80 + 150 * (wk_temp - 1000) / 3000;
if (wk_temp == 1000)
compensation -= 10;
if (wk_temp != 0) {
if (ad_value > (compensation + gZerop_ad))
ad_value -= compensation;
}
if (cool_tmp > 400)
cool_tmp = 400; //cap cool temp at 40C
return (ad_value * 1000 + 806 * cool_tmp - gZerop_ad * 1000) / 806;
}
/*******************************************************************************
Function:Start_Watchdog
Description: Starts the system watchdog timer
*******************************************************************************/
u32 Start_Watchdog(u32 ms) {
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
/* IWDG counter clock: 40KHz(LSI) / 32 = 1.25 KHz (min:0.8ms -- max:3276.8ms */
IWDG_SetPrescaler(IWDG_Prescaler_32);
/* Set counter reload value to XXms */
IWDG_SetReload(ms * 10 / 8);
/* Reload IWDG counter */
IWDG_ReloadCounter();
/* Enable IWDG (the LSI oscillator will be enabled by hardware) */
IWDG_Enable();
return 1;
}
/*******************************************************************************
Function:Clear_Watchdog
Description:Resets the watchdog timer
*******************************************************************************/
void Clear_Watchdog(void) {
IWDG_ReloadCounter();
}
/******************************** END OF FILE *********************************/

View File

@@ -7,17 +7,16 @@
#include "I2C.h"
volatile uint32_t system_Ticks;
void delayMs(uint32_t ticks)
{
uint32_t endtime = ticks+millis();
while(millis()<endtime);
void delayMs(uint32_t ticks) {
uint32_t endtime = ticks + millis();
while (millis() < endtime)
;
}
/******************************************************************************/
/* Processor Exceptions Handlers */
/******************************************************************************/
void NMI_Handler(void) {
;
}
@@ -72,66 +71,144 @@ void TIM2_IRQHandler(void) {
void TIM3_IRQHandler(void) {
TIM3_ISR();
}
volatile uint32_t lastKeyPress;
volatile uint16_t keyState;
volatile uint32_t lastMovement;
//EXTI IRQ
void EXTI9_5_IRQHandler(void) {
//we are interested in line 9 and line 6
if (EXTI_GetITStatus(EXTI_Line9) != RESET) {
if (GPIO_ReadInputDataBit(GPIOA, KEY_A) == SET)
keyState &= ~(BUT_A);
else
keyState |= BUT_A;
EXTI_ClearITPendingBit(EXTI_Line9);
} else if (EXTI_GetITStatus(EXTI_Line6) != RESET) {
if (GPIO_ReadInputDataBit(GPIOA, KEY_B) == SET)
keyState &= ~(BUT_B);
else
keyState |= BUT_B;
EXTI_ClearITPendingBit(EXTI_Line6);
}
lastKeyPress = millis();
}
void WWDG_IRQHandler(void) {}
void PVD_IRQHandler(void) {}
/*********************** UNUSED IRQ *****************************************/
void WWDG_IRQHandler(void) {
}
void PVD_IRQHandler(void) {
}
void TAMPER_IRQHandler(void) {}
void RTC_IRQHandler(void){}
void FLASH_IRQHandler(void){}
void RCC_IRQHandler(void){}
void EXTI0_IRQHandler(void){}
void EXTI1_IRQHandler(void){}
void EXTI2_IRQHandler(void){}
void EXTI3_IRQHandler(void){}
void EXTI4_IRQHandler(void){}
void DMA1_Channel1_IRQHandler(void){}
void DMA1_Channel2_IRQHandler(void){}
void DMA1_Channel3_IRQHandler(void){}
void DMA1_Channel4_IRQHandler(void){}
void DMA1_Channel5_IRQHandler(void){}
void DMA1_Channel6_IRQHandler(void){}
void DMA1_Channel7_IRQHandler(void){}
void ADC1_2_IRQHandler(void){}
void USB_HP_CAN1_TX_IRQHandler(void){}
void CAN1_RX1_IRQHandler(void){}
void CAN1_SCE_IRQHandler(void){}
void EXTI9_5_IRQHandler(void){}
void TIM1_BRK_IRQHandler(void){}
void TIM1_UP_IRQHandler(void){}
void TIM1_TRG_COM_IRQHandler(void){}
void TIM1_CC_IRQHandler(void){}
void TIM4_IRQHandler(void){}
void I2C1_EV_IRQHandler(void){}
void I2C1_ER_IRQHandler(void){}
void I2C2_EV_IRQHandler(void){}
void I2C2_ER_IRQHandler(void){}
void SPI1_IRQHandler(void){}
void SPI2_IRQHandler(void){}
void USART1_IRQHandler(void){}
void USART2_IRQHandler(void){}
void USART3_IRQHandler(void){}
void EXTI15_10_IRQHandler(void){}
void RTCAlarm_IRQHandler(void){}
void USBWakeUp_IRQHandler(void){}
void TIM8_BRK_IRQHandler(void){}
void TIM8_UP_IRQHandler(void){}
void TIM8_TRG_COM_IRQHandler(void){}
void TIM8_CC_IRQHandler(void){}
void ADC3_IRQHandler(void){}
void FSMC_IRQHandler(void){}
void SDIO_IRQHandler(void){}
void TIM5_IRQHandler(void){}
void SPI3_IRQHandler(void){}
void UART4_IRQHandler(void){}
void UART5_IRQHandler(void){}
void TIM6_IRQHandler(void){}
void TIM7_IRQHandler(void){}
void DMA2_Channel1_IRQHandler(void){}
void DMA2_Channel2_IRQHandler(void){}
void DMA2_Channel3_IRQHandler(void) {}
void DMA2_Channel4_5_IRQHandler(void){}
void TAMPER_IRQHandler(void) {
}
void RTC_IRQHandler(void) {
}
void FLASH_IRQHandler(void) {
}
void RCC_IRQHandler(void) {
}
void EXTI0_IRQHandler(void) {
}
void EXTI1_IRQHandler(void) {
}
void EXTI2_IRQHandler(void) {
}
void EXTI3_IRQHandler(void) {
}
void EXTI4_IRQHandler(void) {
}
void DMA1_Channel1_IRQHandler(void) {
}
void DMA1_Channel2_IRQHandler(void) {
}
void DMA1_Channel3_IRQHandler(void) {
}
void DMA1_Channel4_IRQHandler(void) {
}
void DMA1_Channel5_IRQHandler(void) {
}
void DMA1_Channel6_IRQHandler(void) {
}
void DMA1_Channel7_IRQHandler(void) {
}
void ADC1_2_IRQHandler(void) {
}
void USB_HP_CAN1_TX_IRQHandler(void) {
}
void CAN1_RX1_IRQHandler(void) {
}
void CAN1_SCE_IRQHandler(void) {
}
void TIM1_BRK_IRQHandler(void) {
}
void TIM1_UP_IRQHandler(void) {
}
void TIM1_TRG_COM_IRQHandler(void) {
}
void TIM1_CC_IRQHandler(void) {
}
void TIM4_IRQHandler(void) {
}
void I2C1_EV_IRQHandler(void) {
}
void I2C1_ER_IRQHandler(void) {
}
void I2C2_EV_IRQHandler(void) {
}
void I2C2_ER_IRQHandler(void) {
}
void SPI1_IRQHandler(void) {
}
void SPI2_IRQHandler(void) {
}
void USART1_IRQHandler(void) {
}
void USART2_IRQHandler(void) {
}
void USART3_IRQHandler(void) {
}
void EXTI15_10_IRQHandler(void) {
}
void RTCAlarm_IRQHandler(void) {
}
void USBWakeUp_IRQHandler(void) {
}
void TIM8_BRK_IRQHandler(void) {
}
void TIM8_UP_IRQHandler(void) {
}
void TIM8_TRG_COM_IRQHandler(void) {
}
void TIM8_CC_IRQHandler(void) {
}
void ADC3_IRQHandler(void) {
}
void FSMC_IRQHandler(void) {
}
void SDIO_IRQHandler(void) {
}
void TIM5_IRQHandler(void) {
}
void SPI3_IRQHandler(void) {
}
void UART4_IRQHandler(void) {
}
void UART5_IRQHandler(void) {
}
void TIM6_IRQHandler(void) {
}
void TIM7_IRQHandler(void) {
}
void DMA2_Channel1_IRQHandler(void) {
}
void DMA2_Channel2_IRQHandler(void) {
}
void DMA2_Channel3_IRQHandler(void) {
}
void DMA2_Channel4_5_IRQHandler(void) {
}
/********************************* END OF FILE ******************************/

View File

@@ -15,8 +15,7 @@
#include "Oled.h"
#include "MMA8652FC.h"
#include "I2C.h"
#include "CTRL.h"
#include "UI.h"
//------------------------------------------------------------------//
static int IIC_RegWrite(u8 reg, u8 data);

View File

@@ -11,54 +11,46 @@
#include <string.h>
#include <stdio.h>
#include "APP_Version.h"
#include "Modes.h"
#include "Bios.h"
#include "I2C.h"
#include "MMA8652FC.h"
#include "UI.h"
#include "Oled.h"
#include "CTRL.h"
#include "Hardware.h"
#include "Interrupt.h"
int main(void) {
RCC_Config(); //setup system clock
//NVIC_Config(0x4000);
//NVIC_Config(0x4000);//this shifts the NVIC table to be offset
NVIC_Config(0x0000);
Init_Timer2(); //init the timers
GPIO_Config(); //setup all the GPIO pins
Init_EXTI();
//Init_Timer2(); //init the timers
Init_Timer3();
I2C_Configuration(); //init the i2c bus
Adc_Init(); //init adc and dma
StartUp_Accelerated(); //start the accelerometer
System_Init(); //load known safe values
Init_Oled(); //init the OLED display
Clear_Screen(); //clear the display buffer to black
Init_Gtime(); //init the count down timers
APP_Init(); //pick operating mode via input voltage
Pid_Init(); //init the pid to starting values
Set_gKey(NO_KEY); //reset keys to all off
systemSettings.SleepTemp = 200;
systemSettings.SleepTime = 1;
systemSettings.SolderingTemp = 320;
readIronTemp(239);//load the default calibration value
//OLED_DrawString("TEST012",7);
for (;;) {
/*for (;;) {
OLED_DrawTwoNumber((millis() / 100) % 100, (millis()/100)%80);
}
Start_Watchdog(3000); //start the system watchdog as 3 seconds
OLED_DrawTwoNumber((millis() / 100) % 100, (millis() / 100) % 80);
}*/
//Start_Watchdog(3000); //start the system watchdog as 3 seconds
while (1) {
Clear_Watchdog(); //reset the Watchdog
if (Get_CtrlStatus() != USB_POWER && LEAVE_WAIT_TIMER== 0) {
Check_Accelerated(); //update readings from the accelerometer
LEAVE_WAIT_TIMER = 50;//reset timer so we dont poll accelerometer for another 500ms
}
OLed_Display(); //Draw in the Oled display for this mode
Status_Tran(); //Handle user input and mode changing
// Clear_Watchdog(); //reset the Watchdog
ProcessUI();
DrawUI();
}
}
/******************************** END OF FILE *********************************/

View File

@@ -7,18 +7,18 @@
#include "Modes.h"
//This does the required processing and state changes
void ProcessUI() {
uint8_t Buttons = Get_gKey(); //read the buttons status
uint8_t Buttons = getButtons(); //read the buttons status
if (millis() - LastButtonPushTime < 50)
if (millis() - getLastButtonPress() < 100)
Buttons = 0;
//rough prevention for debouncing and allocates settling time
//OLED_DrawThreeNumber(Buttons, 0);
switch (operatingMode) {
case STARTUP:
if (Buttons & KEY_A) {
if (Buttons & BUT_A) {
//A key pressed so we are moving to soldering mode
operatingMode = SOLDERING;
} else if (Buttons & KEY_B) {
} else if (Buttons & BUT_B) {
//B Button was pressed so we are moving to the Settings menu
operatingMode = SETTINGS;
}
@@ -26,42 +26,41 @@ void ProcessUI() {
break;
case SOLDERING:
//We need to check the buttons if we need to jump out
if (Buttons & KEY_A) {
if (Buttons & BUT_A) {
//A key pressed so we are moving to temp set
operatingMode = TEMP_ADJ;
} else if (Buttons & KEY_B) {
} else if (Buttons & BUT_B) {
//B Button was pressed so we are moving back to idle
operatingMode = STARTUP;
} else {
//We need to check the timer for movement in case we need to goto idle
if (millis() - LastMovementTime > (systemSettings.SleepTime * 60000)
&& millis() - LastMovementTime
> (systemSettings.SleepTime * 60000)) {
operatingMode = SLEEP; //Goto Sleep Mode
return;
}
if (systemSettings.movementEnabled)
if (millis() - getLastMovement()
> (systemSettings.SleepTime * 60000)) {
operatingMode = SLEEP; //Goto Sleep Mode
return;
}
//If no buttons pushed we need to read the current temperatures
// and then setup the drive signal time for the iron
}
break;
case TEMP_ADJ:
if (Buttons & KEY_A) {
if (Buttons & BUT_A) {
//A key pressed so we are moving down in temp
} else if (Buttons & KEY_B) {
} else if (Buttons & BUT_B) {
//B key pressed so we are moving up in temp
} 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() - LastButtonPushTime > 3000)
if (millis() - getLastButtonPress() > 3000)
operatingMode = SOLDERING;
}
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 (Buttons & KEY_A) {
if (Buttons & BUT_A) {
//A key iterates through the menu
if (settingsPage == 2) {
//Roll off the end
@@ -70,7 +69,7 @@ void ProcessUI() {
//TODO Save settings
} else
++settingsPage; //move to the next option
} else if (Buttons & KEY_B) {
} else if (Buttons & BUT_B) {
//B changes the value selected
switch (settingsPage) {
case UVLO:
@@ -97,6 +96,17 @@ void ProcessUI() {
break;
case SLEEP:
//The iron is sleeping at a lower temperature due to lack of movement
if (Buttons & BUT_A) {
//A Button was pressed so we are moving back to soldering
operatingMode = SOLDERING;
} else if (Buttons & BUT_B) {
//B Button was pressed so we are moving back to soldering
operatingMode = SOLDERING;
} else if (systemSettings.movementEnabled)
if (millis() - getLastMovement() > 100) {
operatingMode = SOLDERING; //Goto active mode again
return;
}
break;
default:
@@ -109,30 +119,35 @@ void DrawUI() {
case STARTUP:
//We are chilling in the idle mode
//Check if movement in the last 5 minutes , if not sleep OLED
if (millis() - LastMovementTime > (5 * 60 * 1000)) {
if (millis() - getLastMovement() > (5 * 60 * 1000)) {
//OLED off
Oled_DisplayOff();
} else {
Oled_DisplayOn();
OLED_DrawString("IDLE ", 0); //write the word IDLE
OLED_DrawString("IDLE ", 6); //write the word IDLE
}
break;
case SOLDERING:
//The user is soldering
//We draw in the current system temp and an indicator if the iron is heating or not
//First lets draw the current tip temp
//OLED_DrawString("SOLD ", 6);
OLED_DrawThreeNumber(readIronTemp(0), 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_DrawString("TEMP ", 6);
break;
case SETTINGS:
//We are prompting the user the setting name
OLED_DrawString("SETT ", 6);
break;
case SLEEP:
//The iron is in sleep temp mode
//Draw in temp and sleep
OLED_DrawString("SLEP ", 6);
break;
default:
break;

View File

@@ -14,25 +14,15 @@
#include "Oled.h"
#include "Bios.h"
#include "I2C.h"
#include "Hardware.h"
#include "UI.h"
#include "Font.h"
//Setup params depending on oled model
#ifdef SSD1316
u8 gOled_param[50] = {0x80,0xAE,0x80,0x00,0x80,0x10,0x80,0x40,0x80,0xB0,0x80,
0x81,0x80,0xFF,0x80,0xA0,0x80,0xA6,0x80,0xA8,0x80,0x1F,
0x80,0xC8,0x80,0xD3,0x80,0x00,0x80,0xD5,0x80,0x80,0x80,
0xD9,0x80,0x22,0x80,0xDA,0x80,0x12,0x80,0xDB,0x80,0x40,
0x80,0x8D,0x80,0x14,0x80,0xAF,
};
#else
u8 gOled_param[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 };
#endif
/*******************************************************************************
*******************************************************************************/
@@ -152,16 +142,10 @@ void Init_Oled(void) {
u8 param_len;
OLED_RST();
Delay_Ms(2); //reset the oled
delayMs(2); //reset the oled
OLED_ACT();
Delay_Ms(2);
#ifdef SSD1316
param_len = 50;
#else
delayMs(2);
param_len = 46;
#endif
I2C_PageWrite((u8 *) gOled_param, param_len, DEVICEADDR_OLED);
}
@@ -187,11 +171,16 @@ void OLED_DrawChar(char c, uint8_t x) {
u8* ptr;
ptr = (u8*) FONT;
if (c >= 'A' && c <= 'Z') {
ptr += (c - 'A' + 10) * (14 * 2);
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);
}
Oled_DrawArea(x, 0, 14, 16, (u8*) ptr);
}
/*
@@ -200,7 +189,20 @@ void OLED_DrawChar(char c, uint8_t x) {
void OLED_DrawTwoNumber(uint8_t in, uint8_t x) {
OLED_DrawChar(in / 10, x);
OLED_DrawChar(in % 10, x + 14);
}
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);
}
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 + 32);
}
/******************************** END OF FILE *********************************/

File diff suppressed because it is too large Load Diff