Accelerometer into motion deteection using App Note

This commit is contained in:
Ben V. Brown
2016-09-29 13:16:21 +10:00
parent c98e4126b2
commit d4fbe99b8b
10 changed files with 240 additions and 430 deletions

View File

@@ -28,7 +28,7 @@
</builder>
<tool id="fr.ac6.managedbuild.tool.gnu.cross.c.compiler.1500724168" name="MCU GCC Compiler" superClass="fr.ac6.managedbuild.tool.gnu.cross.c.compiler">
<option id="fr.ac6.managedbuild.gnu.c.compiler.option.optimization.level.963224364" name="Optimization Level" superClass="fr.ac6.managedbuild.gnu.c.compiler.option.optimization.level" useByScannerDiscovery="false" value="fr.ac6.managedbuild.gnu.c.optimization.level.more" valueType="enumerated"/>
<option id="gnu.c.compiler.option.debugging.level.400507088" name="Debug Level" superClass="gnu.c.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.c.debugging.level.default" valueType="enumerated"/>
<option id="gnu.c.compiler.option.debugging.level.400507088" name="Debug Level" superClass="gnu.c.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.c.debugging.level.max" valueType="enumerated"/>
<option id="gnu.c.compiler.option.include.paths.1436405353" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/inc}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/StdPeriph_Driver/inc}&quot;"/>

View File

@@ -1,51 +1,37 @@
/********************* (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>
*******************************************************************************/
/*
* Setup fuctions for the basic hardware present in the system
*/
#ifndef __BIOS_H
#define __BIOS_H
#include "stm32f10x.h"
#include "S100V0_1.h"
#include "Analog.h"
extern volatile u32 gTime[];
#include "S100V0_1.h"/*For pin definitions*/
#include "Analog.h"/*So that we can attach the DMA to the output array*/
extern volatile uint32_t gHeat_cnt;
inline void setIronTimer(uint32_t time) {
gHeat_cnt = time;
}
inline uint32_t getIronTimer()
{
return gHeat_cnt;
inline uint32_t getIronTimer() {
return gHeat_cnt;
}
#define LOW 0
#define HIGH 1
#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
/*Get set the remaining toggles of the heater output*/
u32 Get_HeatingTime(void);
void Set_HeatingTime(u32 heating_time);
u16 Get_AdcValue(u8 i);
void Init_Gtime(void);
void USB_Port(u8 state);
void NVIC_Config(u16 tab_offset);
void RCC_Config(void);
void GPIO_Config(void);
void Adc_Init(void);
void Init_Timer2(void);
void Init_Timer3(void);
void TIM2_ISR(void);
/*Interrupts*/
void TIM3_ISR(void);
void Init_EXTI(void);
/*Watchdog*/
void Start_Watchdog(uint32_t ms);
void Clear_Watchdog(void);
#endif
/********************************* END OF FILE ********************************/

View File

@@ -42,8 +42,13 @@ inline uint32_t millis() {
inline uint32_t getLastButtonPress() {
return lastKeyPress;
}
inline uint32_t resetLastButtonPress() {
inline void resetLastButtonPress() {
lastKeyPress = millis();
}
inline void resetButtons() {
lastKeyPress = millis();
keyState = 0;
}
inline uint32_t getLastMovement() {
return lastMovement;

View File

@@ -1,19 +1,90 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. **********************
File Name : MMA8652FC.h
Version : S100 APP Ver 2.11
Description:
Author : Celery
Data: 2015/07/07
History:
2015/07/07 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
*******************************************************************************/
/*
* MMA8652FC.*
* Files for the built in accelerometer from NXP.
* This sets the unit up in motion detection mode with an interrupt on movement
* This interrupt is fed to PB5 which catches it via EXTI5
*
* http://cache.freescale.com/files/sensors/doc/data_sheet/MMA8652FC.pdf
*
* EXTI Motion config setup values lifted from AN4070from NXP
*
* Ben V. Brown - <ralim@ralimtek.com>
*/
#ifndef __MMA8652FC__H
#define __MMA8652FC__H
void StartUp_Acceleromter(void);//This is the only function we expose
//--------------MMA8652 Device ID----------------------------------------------//
#define DEVICE_ADDR 0X1D
//--------------MMA8652 Registers-------------------------------------------//
#define STATUS_REG 0x00 // STATUS Register
#define OUT_X_MSB_REG 0x01 // [7:0] are 8 MSBs of the 14-bit X-axis sample
#define OUT_X_LSB_REG 0x02 // [7:2] are the 6 LSB of 14-bit X-axis sample
#define OUT_Y_MSB_REG 0x03 // [7:0] are 8 MSBs of the 14-bit Y-axis sample
#define OUT_Y_LSB_REG 0x04 // [7:2] are the 6 LSB of 14-bit Y-axis sample
#define OUT_Z_MSB_REG 0x05 // [7:0] are 8 MSBs of the 14-bit Z-axis sample
#define OUT_Z_LSB_REG 0x06 // [7:2] are the 6 LSB of 14-bit Z-axis sample
#define F_SETUP_REG 0x09 // F_SETUP FIFO Setup Register
#define TRIG_CFG_REG 0x0A // TRIG_CFG Map of FIFO data capture events
#define SYSMOD_REG 0x0B // SYSMOD System Mode Register
#define INT_SOURCE_REG 0x0C // INT_SOURCE System Interrupt Status Register
#define WHO_AM_I_REG 0x0D // WHO_AM_I Device ID Register
#define XYZ_DATA_CFG_REG 0x0E // XYZ_DATA_CFG Sensor Data Configuration Register
#define HP_FILTER_CUTOFF_REG 0x0F // HP_FILTER_CUTOFF High Pass Filter Register
#define PL_STATUS_REG 0x10 // PL_STATUS Portrait/Landscape Status Register
#define PL_CFG_REG 0x11 // PL_CFG Portrait/Landscape Configuration Register
#define PL_COUNT_REG 0x12 // PL_COUNT Portrait/Landscape Debounce Register
#define PL_BF_ZCOMP_REG 0x13 // PL_BF_ZCOMP Back/Front and Z Compensation Register
#define P_L_THS_REG 0x14 // P_L_THS Portrait to Landscape Threshold Register
#define FF_MT_CFG_REG 0x15 // FF_MT_CFG Freefall and Motion Configuration Register
#define FF_MT_SRC_REG 0x16 // FF_MT_SRC Freefall and Motion Source Register
#define FF_MT_THS_REG 0x17 // FF_MT_THS Freefall and Motion Threshold Register
#define FF_MT_COUNT_REG 0x18 // FF_MT_COUNT Freefall Motion Count Register
#define TRANSIENT_CFG_REG 0x1D // TRANSIENT_CFG Transient Configuration Register
#define TRANSIENT_SRC_REG 0x1E // TRANSIENT_SRC Transient Source Register
#define TRANSIENT_THS_REG 0x1F // TRANSIENT_THS Transient Threshold Register
#define TRANSIENT_COUNT_REG 0x20 // TRANSIENT_COUNT Transient Debounce Counter Register
#define PULSE_CFG_REG 0x21 // PULSE_CFG Pulse Configuration Register
#define PULSE_SRC_REG 0x22 // PULSE_SRC Pulse Source Register
#define PULSE_THSX_REG 0x23 // PULSE_THS XYZ Pulse Threshold Registers
#define PULSE_THSY_REG 0x24
#define PULSE_THSZ_REG 0x25
#define PULSE_TMLT_REG 0x26 // PULSE_TMLT Pulse Time Window Register
#define PULSE_LTCY_REG 0x27 // PULSE_LTCY Pulse Latency Timer Register
#define PULSE_WIND_REG 0x28 // PULSE_WIND Second Pulse Time Window Register
#define ASLP_COUNT_REG 0x29 // ASLP_COUNT Auto Sleep Inactivity Timer Register
#define CTRL_REG1 0x2A // CTRL_REG1 System Control 1 Register
#define CTRL_REG2 0x2B // CTRL_REG2 System Control 2 Register
#define CTRL_REG3 0x2C // CTRL_REG3 Interrupt Control Register
#define CTRL_REG4 0x2D // CTRL_REG4 Interrupt Enable Register
#define CTRL_REG5 0x2E // CTRL_REG5 Interrupt Configuration Register
#define OFF_X_REG 0x2F // XYZ Offset Correction Registers
#define OFF_Y_REG 0x30
#define OFF_Z_REG 0x31
//MMA8652FC 7-bit I2C address
#define MMA8652FC_I2C_ADDRESS 0x1D // MMA865xFC 7-bit I2C address is fixed
//MMA8652FC Sensitivity
#define SENSITIVITY_2G 1024
#define SENSITIVITY_4G 512
#define SENSITIVITY_8G 256
#define STATUS_REG 0x00
#define X_MSB_REG 0X01
#define X_LSB_REG 0X02
@@ -27,15 +98,8 @@ History:
#define INT_SOURCE 0X0C
#define DEVICE_ID 0X0D
#define XYZ_DATA_CFG_REG 0X0E
#define CTRL_REG1 0X2A //
#define CTRL_REG2 0X2B //System Control 2 register
#define CTRL_REG3 0X2C //
#define CTRL_REG4 0X2D //Interrupt Enable register
#define CTRL_REG5 0X2E //
//-----STATUS_REG(0X00)-----Bit Define----------------------------------------//
#define ZYXDR_BIT 0X08
//----XYZ_DATA_CFG_REG(0xE)-Bit Define----------------------------------------//
@@ -54,7 +118,7 @@ History:
#define FHZ2 0x5 //12.5hz
#define FHZ1 0x6 //6.25hz
#define FHZ0 0x7 //1.563hz
#define DataRateValue FHZ100
//---------CTRL_REG2(0X2B)Bit Define------------------------------------------//
#define MODS_MASK 0x03 //Oversampling Mode 4
#define Normal_Mode 0x0 //Normal=0,Low Noise Low Power MODS=1,
@@ -70,16 +134,5 @@ History:
#define INT_EN_FF_MT 1<<2 //Freefall/Motion Interrupt Enable
#define INT_EN_DRDY 1<<0 //Data Ready Interrupt Enable
u16 Get_MmaShift(void);
void Set_MmaShift(u16 shift);
u16 Get_MmaActive(void);
void MMA865x_Standby(void);
void MMA865x_Active(void);
u16 Cheak_XYData(u16 x0,u16 y0,u16 x1,u16 y1);
u16 Update_X(void);
u16 Update_Y(void);
u16 Update_Z(void);
void Check_Accelerated(void);
void StartUp_Accelerated(void);
#endif
/******************************** END OF FILE *********************************/

View File

@@ -119,10 +119,16 @@ void GPIO_Config(void) {
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
GPIO_Init(GPIOB, &GPIO_InitStructure);
//-------- K1 = PA9, K2 = PA6 ----------------------------------------------------------//
//-------- K1 = PA9, K2 = PA6 ----------------------------------------------------------//
GPIO_InitStructure.GPIO_Pin = KEY1_PIN | KEY2_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
GPIO_Init(GPIOA, &GPIO_InitStructure);
//--------INT 1 == PB5 ----------------------------------------------------------//
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
GPIO_Init(GPIOB, &GPIO_InitStructure);
}
/*******************************************************************************
Function: Adc_Init
@@ -200,37 +206,11 @@ void Adc_Init(void) {
ADC_SoftwareStartConvCmd(ADC2, ENABLE);
}
/*******************************************************************************
Function:
Description: Setup Timer2 to fire every 10ms
*******************************************************************************/
void Init_Timer2(void) {
NVIC_InitTypeDef NVIC_InitStructure;
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);
TIM_TimeBaseStructure.TIM_Prescaler = 48 - 1; // (48MHz)/48 = 1MHz
TIM_TimeBaseStructure.TIM_Period = 10000 - 1; // Interrupt per 10mS
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
TIM_ARRPreloadConfig(TIM2, ENABLE);
TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE);
TIM_Cmd(TIM2, ENABLE);
NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
/*******************************************************************************
Function:
Description: Init Timer3 to fire every 50us to be used to control the irons software PWM
This needs to be really fast as there is a cap used between this and the driver circuitry
That prevents astuck mcu heating the tip
*******************************************************************************/
/*
* Init Timer3 to fire every 50us to be used to control the irons software PWM
* This needs to be really fast as there is a cap used between this and the driver circuitry
* That prevents a stuck mcu heating the tip
*/
void Init_Timer3(void) {
NVIC_InitTypeDef NVIC_InitStructure;
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
@@ -260,14 +240,17 @@ void Init_EXTI(void) {
GPIO_EXTILineConfig(GPIO_PortSourceGPIOA,
GPIO_PinSource6 | GPIO_PinSource9);
/* Configure EXTI0 line */
EXTI_InitStructure.EXTI_Line = EXTI_Line6 | EXTI_Line9;
GPIO_EXTILineConfig(GPIO_PortSourceGPIOB,
GPIO_PinSource5); //PB5 == accelerometer
/* Configure EXTI5/6/9 line */
EXTI_InitStructure.EXTI_Line = EXTI_Line5 | 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 */
/* Enable and set EXTI9_5 Interrupt to the lowest priority */
NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0F;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0F;
@@ -275,11 +258,9 @@ void Init_EXTI(void) {
NVIC_Init(&NVIC_InitStructure);
}
/*******************************************************************************
Function:Start_Watchdog
Description: Starts the system watchdog timer
*******************************************************************************/
u32 Start_Watchdog(u32 ms) {
//Start the system watchdog with a timeout specified
//Note you cannot turn this off once you turn it on
void Start_Watchdog(uint32_t ms) {
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
/* IWDG counter clock: 40KHz(LSI) / 32 = 1.25 KHz (min:0.8ms -- max:3276.8ms */
@@ -293,48 +274,32 @@ u32 Start_Watchdog(u32 ms) {
/* Enable IWDG (the LSI oscillator will be enabled by hardware) */
IWDG_Enable();
return 1;
}
/*******************************************************************************
Function:Clear_Watchdog
Description:Resets the watchdog timer
*******************************************************************************/
//Reset the system watchdog
void Clear_Watchdog(void) {
IWDG_ReloadCounter();
}
/*******************************************************************************
Function:TIM2_ISR
Description:Handles Timer 2 tick. (10mS)
Automatically decrements all >0 values in gTime.
Also reads the buttons every 4 ticks
*******************************************************************************/
void TIM2_ISR(void) {
TIM_ClearITPendingBit(TIM2, TIM_IT_Update); // Clear interrupt flag
}
/*******************************************************************************
Function: TIM3_ISR
Description:Sets the output pin as appropriate
If the Heat_cnt >0 then heater on, otherwise off.
*******************************************************************************/
//TIM3_ISR handles the tick of the timer 3 IRQ
void TIM3_ISR(void) {
volatile static u8 heat_flag = 0; //heat flag == used to make the pin toggle
volatile static u8 heat_flag = 0;
//heat flag == used to make the pin toggle
//As the output is passed through a cap, the iron is on whilever we provide a square wave drive output
TIM_ClearITPendingBit(TIM3, TIM_IT_Update); // Clear interrupt flag
TIM_ClearITPendingBit(TIM3, TIM_IT_Update);
// Clear interrupt flag
if (gHeat_cnt > 0) {
--gHeat_cnt;
if (heat_flag)
HEAT_OFF();
HEAT_OFF(); //write the pin off
else
HEAT_ON();
HEAT_ON(); //write the pin on
heat_flag = !heat_flag;
} else {
HEAT_OFF();
HEAT_OFF(); //set the pin low for measurements
heat_flag = 0;
}
}
/******************************** END OF FILE *********************************/

View File

@@ -1,22 +1,19 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. *******************/
/* Brief : Interrupt Service Routines Author : bure */
/******************************************************************************/
#include "Interrupt.h"
#include "Bios.h"
#include "I2C.h"
volatile uint32_t system_Ticks;
volatile uint32_t system_Ticks;
volatile uint32_t lastKeyPress; //millis() at the last button event
volatile uint16_t keyState; //tracks the button status
volatile uint32_t lastMovement; //millis() at last movement event
//Delay in milliseconds using systemTick
void delayMs(uint32_t ticks) {
uint32_t endtime = ticks + millis();
while (millis() < endtime)
;
}
/******************************************************************************/
/* Processor Exceptions Handlers */
/******************************************************************************/
void NMI_Handler(void) {
;
}
@@ -41,56 +38,40 @@ void UsageFault_Handler(void) {
;
}
void SVC_Handler(void) {
}
void DebugMon_Handler(void) {
}
void PendSV_Handler(void) {
}
//Handles the tick of the sysTick events
void SysTick_Handler(void) {
++system_Ticks;
}
/******************************************************************************/
/* Peripherals Interrupt Handlers */
/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */
/* available peripheral interrupt handler's name please refer to the startup */
/* file (startup_stm32f30x.s). */
/******************************************************************************/
void USB_LP_CAN1_RX0_IRQHandler(void) {
}
void TIM2_IRQHandler(void) {
TIM2_ISR();
}
/*Peripheral Interrupts */
void TIM3_IRQHandler(void) {
TIM3_ISR();
}
volatile uint32_t lastKeyPress;
volatile uint16_t keyState;
volatile uint32_t lastMovement;
//EXTI IRQ
//EXTI IRQ handler
//used for buttons and movement
void EXTI9_5_IRQHandler(void) {
//we are interested in line 9 and line 6
//we are interested in line 9 and line 6 for buttons
//Lien 5 == movement
if (EXTI_GetITStatus(EXTI_Line9) != RESET) {
if (GPIO_ReadInputDataBit(GPIOA, KEY_A) == SET)
keyState &= ~(BUT_A);
else
keyState |= BUT_A;
lastKeyPress = millis();
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;
lastKeyPress = millis();
EXTI_ClearITPendingBit(EXTI_Line6);
} else if (EXTI_GetITStatus(EXTI_Line5) != RESET) { //Movement Event
lastMovement = millis();
EXTI_ClearITPendingBit(EXTI_Line5);
}
lastKeyPress = millis();
}
@@ -99,7 +80,6 @@ void WWDG_IRQHandler(void) {
}
void PVD_IRQHandler(void) {
}
void TAMPER_IRQHandler(void) {
}
void RTC_IRQHandler(void) {
@@ -208,6 +188,21 @@ void DMA2_Channel2_IRQHandler(void) {
void DMA2_Channel3_IRQHandler(void) {
}
void DMA2_Channel4_5_IRQHandler(void) {
}
void TIM2_IRQHandler(void) {
}
void SVC_Handler(void) {
}
void DebugMon_Handler(void) {
}
void PendSV_Handler(void) {
}
void USB_LP_CAN1_RX0_IRQHandler(void) {
}
/********************************* END OF FILE ******************************/

View File

@@ -1,251 +1,47 @@
/********************* (C) COPYRIGHT 2015 e-Design Co.,Ltd. **********************
File Name : MMA8652FC.c
Version : S100 APP Ver 2.11
Description:
Author : Celery
Data: 2015/07/07
History:
2016/09/13 Ben V. Brown - English comments and fixing a few errors
2015/07/07 ͳһ<CDB3><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
*******************************************************************************/
/*
* MMA8652FC.*
* Files for the built in accelerometer from NXP.
* This sets the unit up in motion detection mode with an interrupt on movement
* This interrupt is fed to PB5 which catches it via EXTI5
*
* http://cache.freescale.com/files/sensors/doc/data_sheet/MMA8652FC.pdf
*
* EXTI Motion config setup values lifted from AN4070from NXP
*
* Ben V. Brown - <ralim@ralimtek.com>
*/
#include <stdio.h>
#include <string.h>
#include "APP_Version.h"
#include "Bios.h"
#include "Oled.h"
#include "MMA8652FC.h"
#include "I2C.h"
//------------------------------------------------------------------//
static int IIC_RegWrite(u8 reg, u8 data);
static int IIC_RegRead(u8 reg);
static int Read_ZYXDr(void);
u16 gactive = 0, gShift = 0;
u8 gMmatxdata;
typedef struct {
u8 hi;
u8 lo;
} DR_Value;
DR_Value gX_value, gY_value, gZ_value;
/*******************************************************************************
Function:
Description:Returns if the unit is actively being moved
Output: if the unit is active or not.
*******************************************************************************/
u16 Get_MmaActive(void) {
return gactive;
}
/*******************************************************************************
Function: Get_MmaActive
Description:Returns if movement has occured (0==still,1==movement)
*******************************************************************************/
u16 Get_MmaShift(void) {
return gShift;
}
/*******************************************************************************
Function: Set_MmaShift
Description: Set the Shift Value
Input: shift value
*******************************************************************************/
void Set_MmaShift(u16 shift) {
gShift = shift;
}
/*******************************************************************************
Function:IIC_RegWrite
Description:Writes a value to a register
Input:the register, the data
Output: 1 if the write succeeded
*******************************************************************************/
int IIC_RegWrite(u8 reg, u8 data) {
u8 tx_data[20];
void I2C_RegisterWrite(uint8_t reg, uint8_t data) {
u8 tx_data[2];
tx_data[0] = reg;
tx_data[1] = data;
I2C_PageWrite(tx_data, 2, DEVICE_ADDR);
return 1;
}
/*******************************************************************************
Function:IIC_RegRead
Description: Reads a register from I2C, using a single byte addressing scheme
Inputs: uint8_t register to read
Output: 1 if the read worked.
*******************************************************************************/
int IIC_RegRead(u8 reg) {
u8 tx_data[20];
uint8_t I2C_RegisterRead(uint8_t reg) {
u8 tx_data[3];
tx_data[0] = reg;
I2C_PageRead(tx_data, 1, DEVICE_ADDR, reg);
gMmatxdata = tx_data[0];
return 1;
}
/*******************************************************************************
Function: MMA865x_Standby
Description: Put the MMA865 into standby mode
*******************************************************************************/
void MMA865x_Standby(void) {
//Put the sensor into Standby Mode by clearing
// the Active bit of the System Control 1 Register
IIC_RegWrite(CTRL_REG1, 0); //(IIC_RegRead(CTRL_REG1) & ~ ACTIVE_MASK)
}
/*******************************************************************************
Function: MMA865x_Active
Description: Put the MMA865 into active mode
*******************************************************************************/
void MMA865x_Active(void) {
// Put the sensor into Active Mode by setting the
// Active bit of the System Control 1 Register
IIC_RegWrite(CTRL_REG1, ACTIVE_MASK); //(IIC_RegRead(CTRL_REG1) | ACTIVE_MASK)
}
/*******************************************************************************
Function: IIC_RegRead
Description:Setup the MMA865x IC settings
*******************************************************************************/
void StartUp_Accelerated(void) {
//Put the unit into standby state so we can edit its configuration registers
MMA865x_Standby();
//Set the unit to full scale measurement
IIC_RegWrite(XYZ_DATA_CFG_REG, FULL_SCALE_8G); //(IIC_RegRead(XYZ_DATA_CFG_REG) & ~FS_MASK)
//Set the unit to the required update rate (eg 100Hz)
IIC_RegWrite(CTRL_REG1, DataRateValue); //IIC_RegRead(CTRL_REG1)|
return tx_data[0];
IIC_RegWrite(CTRL_REG2, 0); //Normal mode
//Change the unit back to active mode to exit setup and start the readings
MMA865x_Active();
}
/*******************************************************************************
Function: Read_ZYXDr
Description:
Output: 1 if new data, 0 if not
*******************************************************************************/
int Read_ZYXDr(void) {
u8 reg_flag;
u8 ptr, i;
u8 value[6] = { 0, 0, 0, 0, 0, 0 };
//Poll the ZYXDR status bit and wait for it to set
if (IIC_RegRead(STATUS_REG)) { //check we can read the status
reg_flag = gMmatxdata;
if ((reg_flag & ZYXDR_BIT) != 0) { //if new measurement
//Read 12/10-bit XYZ results using a 6 byte IIC access
ptr = X_MSB_REG;
for (i = 0; i < 6; i++) {
if (IIC_RegRead(ptr++) == 0)
break;
void StartUp_Acceleromter(void) {
value[i] = gMmatxdata;
//Copy and save each result as a 16-bit left-justified value
gX_value.hi = value[0];
gX_value.lo = value[1];
gY_value.hi = value[2];
gY_value.lo = value[3];
gZ_value.hi = value[4];
gZ_value.lo = value[5];
return 1;
}
} else
return 0;
}
return 0;
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, 0x10); // Set threshold to about 0.25g
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_REG1, 0x19); // ODR=100 Hz, Active mode
}
/*******************************************************************************
Function: Cheak_XYData
Description: Check the input X,Y for a large enough acceleration to wake the unit
Inputs:x0,y0,x1,y1 to check
Output: if the unit is active
*******************************************************************************/
u16 Cheak_XYData(u16 x0, u16 y0, u16 x1, u16 y1) {
u16 active = 0;
gShift = 0;
if ((x1 > (x0 + 32)) || (x1 < (x0 - 32)))
gShift = 1;
if ((y1 > (y0 + 32)) || (y1 < (y0 - 32)))
gShift = 1;
if ((x1 > (x0 + 16)) || (x1 < (x0 - 16)))
active = 1;
if ((y1 > (y0 + 16)) || (y1 < (y0 - 16)))
active = 1;
return active;
}
/*******************************************************************************
Function: Update_X
Description: Converts the read value for x into an actual properly located value
Output: X
*******************************************************************************/
u16 Update_X(void) {
u16 value, x;
value = ((gX_value.hi << 8) | (gX_value.lo & 0xf0)) >> 4;
if (gX_value.hi > 0x7f)
x = (~value + 1) & 0xfff;
else
x = value & 0xfff;
return x;
}
/*******************************************************************************
Function: Update_Y
Description: Converts the read value for y into an actual properly located value
Output: Y
*******************************************************************************/
u16 Update_Y(void) {
u16 value, y;
value = ((gY_value.hi << 8) | (gY_value.lo & 0xf0)) >> 4;
if (gY_value.hi > 0x7f)
y = (~value + 1) & 0xfff;
else
y = value & 0xfff;
return y;
}
/*******************************************************************************
Function: Update_Z
Description: Converts the read value for z into an actual properly located value
Output: Z
*******************************************************************************/
u16 Update_Z(void) {
u16 value, z;
value = ((gZ_value.hi << 8) | (gZ_value.lo & 0xf0)) >> 4;
if (gZ_value.hi > 0x7f)
z = (~value + 1) & 0xfff;
else
z = value & 0xfff;
return z;
}
/*******************************************************************************
Function: Check_Accelerated
Description:Check if the unit has moved
*******************************************************************************/
void Check_Accelerated(void) {
static u16 x0 = 0, y0 = 0;
u16 x1, y1;
if (Read_ZYXDr()) { //Read the new values from the accelerometer
x1 = Update_X(); //convert the values into usable form
y1 = Update_Y();
} else {
x1 = x0;
y1 = y0; //use old values
gactive = 0;
return;
}
gactive = Cheak_XYData(x0, y0, x1, y1); //gactive == If the unit is moving or not
x0 = x1;
y0 = y1;
}
/******************************** END OF FILE *********************************/

View File

@@ -31,25 +31,20 @@ int main(void) {
I2C_Configuration(); //init the i2c bus
Adc_Init(); //init adc and dma
StartUp_Accelerated(); //start the accelerometer
StartUp_Acceleromter(); //start the accelerometer
Init_Oled(); //init the OLED display
Clear_Screen(); //clear the display buffer to black
systemSettings.SleepTemp = 900;
systemSettings.SleepTime = 1;
systemSettings.SolderingTemp = 1500;
readIronTemp(239,0); //load the default calibration value
systemSettings.SolderingTemp = 1000;
systemSettings.movementEnabled = 1; //we use movement detection
readIronTemp(239, 0); //load the default calibration value
setupPID(); //init the PID values
//OLED_DrawString("TEST012",7);
/*for (;;) {
OLED_DrawTwoNumber((millis() / 100) % 100, (millis() / 100) % 80);
}*/
//Start_Watchdog(3000); //start the system watchdog as 3 seconds
Start_Watchdog(3000); //start the system watchdog as 3 seconds
while (1) {
// Clear_Watchdog(); //reset the Watchdog
Clear_Watchdog(); //reset the Watchdog
ProcessUI();
DrawUI();
delayMs(50);

View File

@@ -9,20 +9,26 @@
void ProcessUI() {
uint8_t Buttons = getButtons(); //read the buttons status
if (millis() - getLastButtonPress() < 150)
if (millis() - getLastButtonPress() < 200)
Buttons = 0;
//rough prevention for debouncing and allocates settling time
//OLED_DrawThreeNumber(Buttons, 0);
switch (operatingMode) {
case STARTUP:
if (Buttons & BUT_A) {
//A key pressed so we are moving to soldering mode
operatingMode = SOLDERING;
resetLastButtonPress();
} else if (Buttons & BUT_B) {
//B Button was pressed so we are moving to the Settings menu
operatingMode = SETTINGS;
resetLastButtonPress();
if ((millis() - getLastButtonPress() > 1000)) {
if (Buttons & BUT_A) {
//A key pressed so we are moving to soldering mode
operatingMode = SOLDERING;
delayMs(500);
resetLastButtonPress();
resetButtons();
} else if (Buttons & BUT_B) {
//B Button was pressed so we are moving to the Settings menu
operatingMode = SETTINGS;
delayMs(500);
resetLastButtonPress();
resetButtons();
}
}
//Nothing else to check here
break;
@@ -32,10 +38,12 @@ void ProcessUI() {
//A 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
operatingMode = STARTUP;
resetLastButtonPress();
resetButtons();
} else {
//We need to check the timer for movement in case we need to goto idle
if (systemSettings.movementEnabled)
@@ -44,10 +52,11 @@ void ProcessUI() {
operatingMode = SLEEP; //Goto Sleep Mode
return;
}
/*if (millis() - getLastButtonPress()
> (systemSettings.SleepTime * 60000))
operatingMode = SLEEP;
return;*/
if (millis() - getLastButtonPress()
> (systemSettings.SleepTime * 60000)) {
operatingMode = SLEEP;
return;
}
//If no buttons pushed we need to perform the PID loop for the iron temp
int32_t newOutput = computePID(systemSettings.SolderingTemp);
if (newOutput >= 0) {
@@ -76,7 +85,7 @@ void ProcessUI() {
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() < 300)
if (millis() - getLastButtonPress() < 400)
return;
if (Buttons & BUT_A) {
@@ -122,10 +131,14 @@ void ProcessUI() {
if (Buttons & BUT_A) {
//A Button was pressed so we are moving back to soldering
operatingMode = SOLDERING;
resetLastButtonPress();
resetButtons();
return;
} else if (Buttons & BUT_B) {
//B Button was pressed so we are moving back to soldering
operatingMode = SOLDERING;
resetLastButtonPress();
resetButtons();
return;
} else if (systemSettings.movementEnabled)
if (millis() - getLastMovement() > 100) {
@@ -148,7 +161,8 @@ 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() - getLastMovement() > (5 * 60 * 1000)) {
if (millis() - getLastMovement() > (5 * 60 * 1000)
&& (millis() - getLastButtonPress() > (5 * 60 * 1000))) {
//OLED off
Oled_DisplayOff();
} else {
@@ -160,10 +174,10 @@ void DrawUI() {
//The user is soldering
{
uint16_t temp = readIronTemp(0, 0);
if (systemSettings.SolderingTemp < temp) {
if (systemSettings.SolderingTemp + 2 < temp) {
OLED_DrawChar('C', 14 * 4);
} else {
if (systemSettings.SolderingTemp - temp < 20) {
if (getIronTimer() < 500) {
OLED_DrawChar(' ', 14 * 4);
} else { //we are heating
OLED_DrawChar('H', 14 * 4);
@@ -172,8 +186,9 @@ void DrawUI() {
}
OLED_DrawThreeNumber(temp / 10, 0);
OLED_DrawChar('C', 14 * 3);
OLED_DrawChar(' ', 14 * 4);
OLED_DrawChar(' ', 14 * 5);
OLED_DrawChar(' ', 14 * 6);
}
break;
case TEMP_ADJ:

View File

@@ -38,8 +38,8 @@ int32_t computePID(uint16_t setpoint) {
}
void setupPID(void) {
pidSettings.kp = 18;
pidSettings.ki = 3;
pidSettings.kp = 22;
pidSettings.ki = 7;
pidSettings.kd = 2;
}