More shuffle

This commit is contained in:
Ben V. Brown
2020-05-29 21:39:12 +10:00
parent fd700aecb9
commit 8d59b072ef
9 changed files with 504 additions and 432 deletions

View File

@@ -0,0 +1,44 @@
#include "defines.h"
#include "stdint.h"
#include "UnitSettings.h"
/*
* BSP.h -- Board Support
*
* This exposes functions that are expected to be implemented to add support for different hardware
*/
#ifndef BSP_BSP_H_
#define BSP_BSP_H_
#ifdef __cplusplus
extern "C" {
#endif
//Called first thing in main() to init the hardware
void preRToSInit();
//Called once the RToS has started for any extra work
void postRToSInit();
// Called to reset the hardware watchdog unit
void resetWatchdog();
//Accepts a output level of 0.. to use to control the tip output PWM
void setTipPWM(uint8_t pulse);
//Returns the Handle temp in C, X10
uint16_t getHandleTemperature();
//Returns the Tip temperature ADC reading in raw units
uint16_t getTipRawTemp(uint8_t refresh);
//Returns the main DC input voltage, using the adjustable divisor + sample flag
uint16_t getInputVoltageX10(uint16_t divisor, uint8_t sample);
// Readers for the two buttons
// !! Returns 1 if held down, 0 if released
uint8_t getButtonA();
uint8_t getButtonB();
// This is a work around that will be called if I2C starts to bug out
// This should toggle the SCL line until SDA goes high to end the current transaction
void unstick_I2C();
#ifdef __cplusplus
}
#endif
#endif /* BSP_BSP_H_ */

View File

@@ -0,0 +1,12 @@
# BSP section for STM32F103 based Miniware products
This folder contains the hardware abstractions required for the TS100, TS80 and probably TS80P soldering irons.
## Main abstractions
* Hardware Init
* -> Should contain all bootstrap to bring the hardware up to an operating point
* -> Two functions are required, a pre and post FreeRToS call
* I2C read/write
* Set PWM for the tip
* Links between IRQ's on the system and the calls in the rest of the firmware

View File

@@ -5,6 +5,7 @@
* Author: Ben V. Brown * Author: Ben V. Brown
*/ */
#include "Setup.h" #include "Setup.h"
#include "Pins.h"
ADC_HandleTypeDef hadc1; ADC_HandleTypeDef hadc1;
ADC_HandleTypeDef hadc2; ADC_HandleTypeDef hadc2;
DMA_HandleTypeDef hdma_adc1; DMA_HandleTypeDef hdma_adc1;
@@ -32,12 +33,8 @@ static void MX_ADC2_Init(void);
void Setup_HAL() { void Setup_HAL() {
SystemClock_Config(); SystemClock_Config();
#ifndef LOCAL_BUILD
__HAL_AFIO_REMAP_SWJ_DISABLE() __HAL_AFIO_REMAP_SWJ_DISABLE()
; ;
#else
__HAL_AFIO_REMAP_SWJ_NOJTAG();
#endif
MX_GPIO_Init(); MX_GPIO_Init();
MX_DMA_Init(); MX_DMA_Init();
@@ -49,8 +46,8 @@ void Setup_HAL() {
MX_IWDG_Init(); MX_IWDG_Init();
HAL_ADC_Start(&hadc2); HAL_ADC_Start(&hadc2);
HAL_ADCEx_MultiModeStart_DMA(&hadc1, (uint32_t*) ADCReadings, 64); // start DMA of normal readings HAL_ADCEx_MultiModeStart_DMA(&hadc1, (uint32_t*) ADCReadings, 64); // start DMA of normal readings
HAL_ADCEx_InjectedStart(&hadc1); // enable injected readings HAL_ADCEx_InjectedStart(&hadc1); // enable injected readings
HAL_ADCEx_InjectedStart(&hadc2); // enable injected readings HAL_ADCEx_InjectedStart(&hadc2); // enable injected readings
} }
// channel 0 -> temperature sensor, 1-> VIN // channel 0 -> temperature sensor, 1-> VIN
@@ -336,7 +333,7 @@ static void MX_TIM2_Init(void) {
HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig); HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig);
sConfigOC.OCMode = TIM_OCMODE_PWM1; sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 255 + 13;//13 -> Delay of 5ms sConfigOC.Pulse = 255 + 13; //13 -> Delay of 5ms
//255 is the largest time period of the drive signal, and then offset ADC sample to be a bit delayed after this //255 is the largest time period of the drive signal, and then offset ADC sample to be a bit delayed after this
/* /*
* It takes 4 milliseconds for output to be stable after PWM turns off. * It takes 4 milliseconds for output to be stable after PWM turns off.

View File

@@ -1,38 +1,38 @@
/* /*
* Setup.h * Setup.h
* *
* Created on: 29Aug.,2017 * Created on: 29Aug.,2017
* Author: Ben V. Brown * Author: Ben V. Brown
*/ */
#ifndef SETUP_H_ #ifndef SETUP_H_
#define SETUP_H_ #define SETUP_H_
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
#include <hardware.h>
#include "stm32f1xx_hal.h" #include "stm32f1xx_hal.h"
extern ADC_HandleTypeDef hadc1; extern ADC_HandleTypeDef hadc1;
extern ADC_HandleTypeDef hadc2; extern ADC_HandleTypeDef hadc2;
extern DMA_HandleTypeDef hdma_adc1; extern DMA_HandleTypeDef hdma_adc1;
extern DMA_HandleTypeDef hdma_i2c1_rx; extern DMA_HandleTypeDef hdma_i2c1_rx;
extern DMA_HandleTypeDef hdma_i2c1_tx; extern DMA_HandleTypeDef hdma_i2c1_tx;
extern I2C_HandleTypeDef hi2c1; extern I2C_HandleTypeDef hi2c1;
extern IWDG_HandleTypeDef hiwdg; extern IWDG_HandleTypeDef hiwdg;
extern TIM_HandleTypeDef htim2; extern TIM_HandleTypeDef htim2;
extern TIM_HandleTypeDef htim3; extern TIM_HandleTypeDef htim3;
void Setup_HAL(); void Setup_HAL();
uint16_t getADC(uint8_t channel); uint16_t getADC(uint8_t channel);
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim); //Since the hal header file does not define this one void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); //Since the hal header file does not define this one
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif
#endif /* SETUP_H_ */ #endif /* SETUP_H_ */

View File

@@ -0,0 +1,19 @@
/*
* preRTOS.c
*
* Created on: 29 May 2020
* Author: Ralim
*/
#include "BSP.h"
#include "Setup.h"
#include "Pins.h"
void preRToSInit() {
/* Reset of all peripherals, Initializes the Flash interface and the Systick.
*/
HAL_Init();
Setup_HAL(); // Setup all the HAL objects
HAL_Delay(50);
HAL_GPIO_WritePin(OLED_RESET_GPIO_Port, OLED_RESET_Pin, GPIO_PIN_SET);
HAL_Delay(50);
}

View File

@@ -1,136 +1,136 @@
#include <hardware.h> #include "Pins.h"
#include "stm32f1xx_hal.h" #include "stm32f1xx_hal.h"
#include "Setup.h" #include "Setup.h"
/** /**
* Initializes the Global MSP. * Initializes the Global MSP.
*/ */
void HAL_MspInit(void) { void HAL_MspInit(void) {
__HAL_RCC_AFIO_CLK_ENABLE() __HAL_RCC_AFIO_CLK_ENABLE()
; ;
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
/* System interrupt init*/ /* System interrupt init*/
/* MemoryManagement_IRQn interrupt configuration */ /* MemoryManagement_IRQn interrupt configuration */
HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0);
/* BusFault_IRQn interrupt configuration */ /* BusFault_IRQn interrupt configuration */
HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0);
/* UsageFault_IRQn interrupt configuration */ /* UsageFault_IRQn interrupt configuration */
HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0);
/* SVCall_IRQn interrupt configuration */ /* SVCall_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0);
/* DebugMonitor_IRQn interrupt configuration */ /* DebugMonitor_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0);
/* PendSV_IRQn interrupt configuration */ /* PendSV_IRQn interrupt configuration */
HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0); HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0);
/* SysTick_IRQn interrupt configuration */ /* SysTick_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SysTick_IRQn, 15, 0); HAL_NVIC_SetPriority(SysTick_IRQn, 15, 0);
} }
void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) { void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) {
GPIO_InitTypeDef GPIO_InitStruct; GPIO_InitTypeDef GPIO_InitStruct;
if (hadc->Instance == ADC1) { if (hadc->Instance == ADC1) {
__HAL_RCC_ADC1_CLK_ENABLE() __HAL_RCC_ADC1_CLK_ENABLE()
; ;
/* ADC1 DMA Init */ /* ADC1 DMA Init */
/* ADC1 Init */ /* ADC1 Init */
hdma_adc1.Instance = DMA1_Channel1; hdma_adc1.Instance = DMA1_Channel1;
hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY; hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE; hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc1.Init.MemInc = DMA_MINC_ENABLE; hdma_adc1.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
hdma_adc1.Init.Mode = DMA_CIRCULAR; hdma_adc1.Init.Mode = DMA_CIRCULAR;
hdma_adc1.Init.Priority = DMA_PRIORITY_VERY_HIGH; hdma_adc1.Init.Priority = DMA_PRIORITY_VERY_HIGH;
HAL_DMA_Init(&hdma_adc1); HAL_DMA_Init(&hdma_adc1);
__HAL_LINKDMA(hadc, DMA_Handle, hdma_adc1); __HAL_LINKDMA(hadc, DMA_Handle, hdma_adc1);
/* ADC1 interrupt Init */ /* ADC1 interrupt Init */
HAL_NVIC_SetPriority(ADC1_2_IRQn, 15, 0); HAL_NVIC_SetPriority(ADC1_2_IRQn, 15, 0);
HAL_NVIC_EnableIRQ(ADC1_2_IRQn); HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
} else { } else {
__HAL_RCC_ADC2_CLK_ENABLE() __HAL_RCC_ADC2_CLK_ENABLE()
; ;
/**ADC2 GPIO Configuration /**ADC2 GPIO Configuration
PB0 ------> ADC2_IN8 PB0 ------> ADC2_IN8
PB1 ------> ADC2_IN9 PB1 ------> ADC2_IN9
*/ */
GPIO_InitStruct.Pin = TIP_TEMP_Pin; GPIO_InitStruct.Pin = TIP_TEMP_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* ADC2 interrupt Init */ /* ADC2 interrupt Init */
HAL_NVIC_SetPriority(ADC1_2_IRQn, 15, 0); HAL_NVIC_SetPriority(ADC1_2_IRQn, 15, 0);
HAL_NVIC_EnableIRQ(ADC1_2_IRQn); HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
} }
} }
void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c) { void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c) {
GPIO_InitTypeDef GPIO_InitStruct; GPIO_InitTypeDef GPIO_InitStruct;
/**I2C1 GPIO Configuration /**I2C1 GPIO Configuration
PB6 ------> I2C1_SCL PB6 ------> I2C1_SCL
PB7 ------> I2C1_SDA PB7 ------> I2C1_SDA
*/ */
GPIO_InitStruct.Pin = SCL_Pin | SDA_Pin; GPIO_InitStruct.Pin = SCL_Pin | SDA_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* Peripheral clock enable */ /* Peripheral clock enable */
__HAL_RCC_I2C1_CLK_ENABLE() __HAL_RCC_I2C1_CLK_ENABLE()
; ;
/* I2C1 DMA Init */ /* I2C1 DMA Init */
/* I2C1_RX Init */ /* I2C1_RX Init */
hdma_i2c1_rx.Instance = DMA1_Channel7; hdma_i2c1_rx.Instance = DMA1_Channel7;
hdma_i2c1_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; hdma_i2c1_rx.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_i2c1_rx.Init.PeriphInc = DMA_PINC_DISABLE; hdma_i2c1_rx.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_i2c1_rx.Init.MemInc = DMA_MINC_ENABLE; hdma_i2c1_rx.Init.MemInc = DMA_MINC_ENABLE;
hdma_i2c1_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; hdma_i2c1_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_i2c1_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; hdma_i2c1_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_i2c1_rx.Init.Mode = DMA_NORMAL; hdma_i2c1_rx.Init.Mode = DMA_NORMAL;
hdma_i2c1_rx.Init.Priority = DMA_PRIORITY_LOW; hdma_i2c1_rx.Init.Priority = DMA_PRIORITY_LOW;
HAL_DMA_Init(&hdma_i2c1_rx); HAL_DMA_Init(&hdma_i2c1_rx);
__HAL_LINKDMA(hi2c, hdmarx, hdma_i2c1_rx); __HAL_LINKDMA(hi2c, hdmarx, hdma_i2c1_rx);
/* I2C1_TX Init */ /* I2C1_TX Init */
hdma_i2c1_tx.Instance = DMA1_Channel6; hdma_i2c1_tx.Instance = DMA1_Channel6;
hdma_i2c1_tx.Init.Direction = DMA_MEMORY_TO_PERIPH; hdma_i2c1_tx.Init.Direction = DMA_MEMORY_TO_PERIPH;
hdma_i2c1_tx.Init.PeriphInc = DMA_PINC_DISABLE; hdma_i2c1_tx.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_i2c1_tx.Init.MemInc = DMA_MINC_ENABLE; hdma_i2c1_tx.Init.MemInc = DMA_MINC_ENABLE;
hdma_i2c1_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; hdma_i2c1_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_i2c1_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; hdma_i2c1_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_i2c1_tx.Init.Mode = DMA_NORMAL; hdma_i2c1_tx.Init.Mode = DMA_NORMAL;
hdma_i2c1_tx.Init.Priority = DMA_PRIORITY_MEDIUM; hdma_i2c1_tx.Init.Priority = DMA_PRIORITY_MEDIUM;
HAL_DMA_Init(&hdma_i2c1_tx); HAL_DMA_Init(&hdma_i2c1_tx);
__HAL_LINKDMA(hi2c, hdmatx, hdma_i2c1_tx); __HAL_LINKDMA(hi2c, hdmatx, hdma_i2c1_tx);
/* I2C1 interrupt Init */ /* I2C1 interrupt Init */
HAL_NVIC_SetPriority(I2C1_EV_IRQn, 15, 0); HAL_NVIC_SetPriority(I2C1_EV_IRQn, 15, 0);
HAL_NVIC_EnableIRQ(I2C1_EV_IRQn); HAL_NVIC_EnableIRQ(I2C1_EV_IRQn);
HAL_NVIC_SetPriority(I2C1_ER_IRQn, 15, 0); HAL_NVIC_SetPriority(I2C1_ER_IRQn, 15, 0);
HAL_NVIC_EnableIRQ(I2C1_ER_IRQn); HAL_NVIC_EnableIRQ(I2C1_ER_IRQn);
} }
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base) { void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base) {
if (htim_base->Instance == TIM3) { if (htim_base->Instance == TIM3) {
/* Peripheral clock enable */ /* Peripheral clock enable */
__HAL_RCC_TIM3_CLK_ENABLE() __HAL_RCC_TIM3_CLK_ENABLE()
; ;
} else if (htim_base->Instance == TIM2) { } else if (htim_base->Instance == TIM2) {
/* Peripheral clock enable */ /* Peripheral clock enable */
__HAL_RCC_TIM2_CLK_ENABLE() __HAL_RCC_TIM2_CLK_ENABLE()
; ;
} }
} }

View File

@@ -1,158 +1,158 @@
/** /**
****************************************************************************** ******************************************************************************
* @file stm32f1xx_hal_timebase_TIM.c * @file stm32f1xx_hal_timebase_TIM.c
* @brief HAL time base based on the hardware TIM. * @brief HAL time base based on the hardware TIM.
****************************************************************************** ******************************************************************************
* This notice applies to any and all portions of this file * This notice applies to any and all portions of this file
* that are not between comment pairs USER CODE BEGIN and * that are not between comment pairs USER CODE BEGIN and
* USER CODE END. Other portions of this file, whether * USER CODE END. Other portions of this file, whether
* inserted by the user or by software development tools * inserted by the user or by software development tools
* are owned by their respective copyright owners. * are owned by their respective copyright owners.
* *
* Copyright (c) 2017 STMicroelectronics International N.V. * Copyright (c) 2017 STMicroelectronics International N.V.
* All rights reserved. * All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met: * modification, are permitted, provided that the following conditions are met:
* *
* 1. Redistribution of source code must retain the above copyright notice, * 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer. * this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice, * 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation * this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution. * and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other * 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products * contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission. * derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this * 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or * software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics. * microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under * 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under * this license is void and will automatically terminate your rights under
* this license. * this license.
* *
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
****************************************************************************** ******************************************************************************
*/ */
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "stm32f1xx_hal.h" #include "stm32f1xx_hal.h"
#include "stm32f1xx_hal_tim.h" #include "stm32f1xx_hal_tim.h"
/** @addtogroup STM32F7xx_HAL_Examples /** @addtogroup STM32F7xx_HAL_Examples
* @{ * @{
*/ */
/** @addtogroup HAL_TimeBase /** @addtogroup HAL_TimeBase
* @{ * @{
*/ */
/* Private typedef -----------------------------------------------------------*/ /* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/ /* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/ /* Private variables ---------------------------------------------------------*/
TIM_HandleTypeDef htim1; TIM_HandleTypeDef htim1;
uint32_t uwIncrementState = 0; uint32_t uwIncrementState = 0;
/* Private function prototypes -----------------------------------------------*/ /* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/ /* Private functions ---------------------------------------------------------*/
/** /**
* @brief This function configures the TIM1 as a time base source. * @brief This function configures the TIM1 as a time base source.
* The time source is configured to have 1ms time base with a dedicated * The time source is configured to have 1ms time base with a dedicated
* Tick interrupt priority. * Tick interrupt priority.
* @note This function is called automatically at the beginning of program after * @note This function is called automatically at the beginning of program after
* reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig(). * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig().
* @param TickPriority: Tick interrupt priorty. * @param TickPriority: Tick interrupt priorty.
* @retval HAL status * @retval HAL status
*/ */
HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
{ {
RCC_ClkInitTypeDef clkconfig; RCC_ClkInitTypeDef clkconfig;
uint32_t uwTimclock = 0; uint32_t uwTimclock = 0;
uint32_t uwPrescalerValue = 0; uint32_t uwPrescalerValue = 0;
uint32_t pFLatency; uint32_t pFLatency;
/*Configure the TIM1 IRQ priority */ /*Configure the TIM1 IRQ priority */
HAL_NVIC_SetPriority(TIM1_UP_IRQn, TickPriority ,0); HAL_NVIC_SetPriority(TIM1_UP_IRQn, TickPriority ,0);
/* Enable the TIM1 global Interrupt */ /* Enable the TIM1 global Interrupt */
HAL_NVIC_EnableIRQ(TIM1_UP_IRQn); HAL_NVIC_EnableIRQ(TIM1_UP_IRQn);
/* Enable TIM1 clock */ /* Enable TIM1 clock */
__HAL_RCC_TIM1_CLK_ENABLE(); __HAL_RCC_TIM1_CLK_ENABLE();
/* Get clock configuration */ /* Get clock configuration */
HAL_RCC_GetClockConfig(&clkconfig, &pFLatency); HAL_RCC_GetClockConfig(&clkconfig, &pFLatency);
/* Compute TIM1 clock */ /* Compute TIM1 clock */
uwTimclock = HAL_RCC_GetPCLK2Freq(); uwTimclock = HAL_RCC_GetPCLK2Freq();
/* Compute the prescaler value to have TIM1 counter clock equal to 1MHz */ /* Compute the prescaler value to have TIM1 counter clock equal to 1MHz */
uwPrescalerValue = (uint32_t) ((uwTimclock / 1000000) - 1); uwPrescalerValue = (uint32_t) ((uwTimclock / 1000000) - 1);
/* Initialize TIM1 */ /* Initialize TIM1 */
htim1.Instance = TIM1; htim1.Instance = TIM1;
/* Initialize TIMx peripheral as follow: /* Initialize TIMx peripheral as follow:
+ Period = [(TIM1CLK/1000) - 1]. to have a (1/1000) s time base. + Period = [(TIM1CLK/1000) - 1]. to have a (1/1000) s time base.
+ Prescaler = (uwTimclock/1000000 - 1) to have a 1MHz counter clock. + Prescaler = (uwTimclock/1000000 - 1) to have a 1MHz counter clock.
+ ClockDivision = 0 + ClockDivision = 0
+ Counter direction = Up + Counter direction = Up
*/ */
htim1.Init.Period = (1000000 / 1000) - 1; htim1.Init.Period = (1000000 / 1000) - 1;
htim1.Init.Prescaler = uwPrescalerValue; htim1.Init.Prescaler = uwPrescalerValue;
htim1.Init.ClockDivision = 0; htim1.Init.ClockDivision = 0;
htim1.Init.CounterMode = TIM_COUNTERMODE_UP; htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
if(HAL_TIM_Base_Init(&htim1) == HAL_OK) if(HAL_TIM_Base_Init(&htim1) == HAL_OK)
{ {
/* Start the TIM time Base generation in interrupt mode */ /* Start the TIM time Base generation in interrupt mode */
return HAL_TIM_Base_Start_IT(&htim1); return HAL_TIM_Base_Start_IT(&htim1);
} }
/* Return function status */ /* Return function status */
return HAL_ERROR; return HAL_ERROR;
} }
/** /**
* @brief Suspend Tick increment. * @brief Suspend Tick increment.
* @note Disable the tick increment by disabling TIM1 update interrupt. * @note Disable the tick increment by disabling TIM1 update interrupt.
* @param None * @param None
* @retval None * @retval None
*/ */
void HAL_SuspendTick(void) void HAL_SuspendTick(void)
{ {
/* Disable TIM1 update Interrupt */ /* Disable TIM1 update Interrupt */
__HAL_TIM_DISABLE_IT(&htim1, TIM_IT_UPDATE); __HAL_TIM_DISABLE_IT(&htim1, TIM_IT_UPDATE);
} }
/** /**
* @brief Resume Tick increment. * @brief Resume Tick increment.
* @note Enable the tick increment by Enabling TIM1 update interrupt. * @note Enable the tick increment by Enabling TIM1 update interrupt.
* @param None * @param None
* @retval None * @retval None
*/ */
void HAL_ResumeTick(void) void HAL_ResumeTick(void)
{ {
/* Enable TIM1 Update interrupt */ /* Enable TIM1 Update interrupt */
__HAL_TIM_ENABLE_IT(&htim1, TIM_IT_UPDATE); __HAL_TIM_ENABLE_IT(&htim1, TIM_IT_UPDATE);
} }
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -1,84 +1,84 @@
// This is the stock standard STM interrupt file full of handlers // This is the stock standard STM interrupt file full of handlers
#include "stm32f1xx_hal.h" #include "stm32f1xx_hal.h"
#include "stm32f1xx.h" #include "stm32f1xx.h"
#include "stm32f1xx_it.h" #include "stm32f1xx_it.h"
#include "cmsis_os.h" #include "cmsis_os.h"
#include "Setup.h" #include "Setup.h"
extern TIM_HandleTypeDef htim1; //used for the systick extern TIM_HandleTypeDef htim1; //used for the systick
/******************************************************************************/ /******************************************************************************/
/* Cortex-M3 Processor Interruption and Exception Handlers */ /* Cortex-M3 Processor Interruption and Exception Handlers */
/******************************************************************************/ /******************************************************************************/
void NMI_Handler(void) { void NMI_Handler(void) {
} }
//We have the assembly for a breakpoint trigger here to halt the system when a debugger is connected //We have the assembly for a breakpoint trigger here to halt the system when a debugger is connected
// Hardfault handler, often a screwup in the code // Hardfault handler, often a screwup in the code
void HardFault_Handler(void) { void HardFault_Handler(void) {
} }
// Memory management unit had an error // Memory management unit had an error
void MemManage_Handler(void) { void MemManage_Handler(void) {
} }
// Prefetcher or busfault occured // Prefetcher or busfault occured
void BusFault_Handler(void) { void BusFault_Handler(void) {
} }
void UsageFault_Handler(void) { void UsageFault_Handler(void) {
} }
void DebugMon_Handler(void) { void DebugMon_Handler(void) {
} }
// Systick is used by FreeRTOS tick // Systick is used by FreeRTOS tick
void SysTick_Handler(void) { void SysTick_Handler(void) {
osSystickHandler(); osSystickHandler();
} }
/******************************************************************************/ /******************************************************************************/
/* STM32F1xx Peripheral Interrupt Handlers */ /* STM32F1xx Peripheral Interrupt Handlers */
/* Add here the Interrupt Handlers for the used peripherals. */ /* Add here the Interrupt Handlers for the used peripherals. */
/* For the available peripheral interrupt handler names, */ /* For the available peripheral interrupt handler names, */
/* please refer to the startup file. */ /* please refer to the startup file. */
/******************************************************************************/ /******************************************************************************/
// DMA used to move the ADC readings into system ram // DMA used to move the ADC readings into system ram
void DMA1_Channel1_IRQHandler(void) { void DMA1_Channel1_IRQHandler(void) {
HAL_DMA_IRQHandler(&hdma_adc1); HAL_DMA_IRQHandler(&hdma_adc1);
} }
//ADC interrupt used for DMA //ADC interrupt used for DMA
void ADC1_2_IRQHandler(void) { void ADC1_2_IRQHandler(void) {
HAL_ADC_IRQHandler(&hadc1); HAL_ADC_IRQHandler(&hadc1);
} }
//Timer 1 has overflowed, used for HAL ticks //Timer 1 has overflowed, used for HAL ticks
void TIM1_UP_IRQHandler(void) { void TIM1_UP_IRQHandler(void) {
HAL_TIM_IRQHandler(&htim1); HAL_TIM_IRQHandler(&htim1);
} }
//Timer 3 is used for the PWM output to the tip //Timer 3 is used for the PWM output to the tip
void TIM3_IRQHandler(void) { void TIM3_IRQHandler(void) {
HAL_TIM_IRQHandler(&htim3); HAL_TIM_IRQHandler(&htim3);
} }
//Timer 2 is used for co-ordination of PWM & ADC //Timer 2 is used for co-ordination of PWM & ADC
void TIM2_IRQHandler(void) { void TIM2_IRQHandler(void) {
HAL_TIM_IRQHandler(&htim2); HAL_TIM_IRQHandler(&htim2);
} }
void I2C1_EV_IRQHandler(void) { void I2C1_EV_IRQHandler(void) {
HAL_I2C_EV_IRQHandler(&hi2c1); HAL_I2C_EV_IRQHandler(&hi2c1);
} }
void I2C1_ER_IRQHandler(void) { void I2C1_ER_IRQHandler(void) {
HAL_I2C_ER_IRQHandler(&hi2c1); HAL_I2C_ER_IRQHandler(&hi2c1);
} }
void DMA1_Channel6_IRQHandler(void) { void DMA1_Channel6_IRQHandler(void) {
HAL_DMA_IRQHandler(&hdma_i2c1_tx); HAL_DMA_IRQHandler(&hdma_i2c1_tx);
} }
void DMA1_Channel7_IRQHandler(void) { void DMA1_Channel7_IRQHandler(void) {
HAL_DMA_IRQHandler(&hdma_i2c1_rx); HAL_DMA_IRQHandler(&hdma_i2c1_rx);
} }

View File

@@ -1,4 +1,7 @@
// By Ben V. Brown - V2.0 of the TS100 firmware // By Ben V. Brown - V2.0 of the TS100 firmware
#include "BSP.h"
#include <MMA8652FC.hpp> #include <MMA8652FC.hpp>
#include <gui.hpp> #include <gui.hpp>
#include <main.hpp> #include <main.hpp>
@@ -45,13 +48,10 @@ void startMOVTask(void const *argument);
// Main sets up the hardware then hands over to the FreeRTOS kernel // Main sets up the hardware then hands over to the FreeRTOS kernel
int main(void) { int main(void) {
/* Reset of all peripherals, Initializes the Flash interface and the Systick. preRToSInit();
*/
HAL_Init();
Setup_HAL(); // Setup all the HAL objects
HAL_IWDG_Refresh(&hiwdg);
setTipX10Watts(0); // force tip off setTipX10Watts(0); // force tip off
FRToSI2C::init(&hi2c1); FRToSI2C::init (&hi2c1);
OLED::initialize(); // start up the LCD OLED::initialize(); // start up the LCD
OLED::setFont(0); // default to bigger font OLED::setFont(0); // default to bigger font
// Testing for which accelerometer is mounted // Testing for which accelerometer is mounted
@@ -69,10 +69,10 @@ int main(void) {
systemSettings.ShutdownTime = 0; // No accel -> disable sleep systemSettings.ShutdownTime = 0; // No accel -> disable sleep
systemSettings.sensitivity = 0; systemSettings.sensitivity = 0;
} }
HAL_IWDG_Refresh(&hiwdg); resetWatchdog();
settingsWereReset = restoreSettings(); // load the settings from flash settingsWereReset = restoreSettings(); // load the settings from flash
HAL_IWDG_Refresh(&hiwdg); resetWatchdog();
/* Create the thread(s) */ /* Create the thread(s) */
/* definition and creation of GUITask */ /* definition and creation of GUITask */
@@ -200,7 +200,7 @@ void startPIDTask(void const *argument __unused) {
setTipX10Watts(x10WattsOut); setTipX10Watts(x10WattsOut);
} }
HAL_IWDG_Refresh(&hiwdg); HAL_IWDG_Refresh (&hiwdg);
} else { } else {
//ADC interrupt timeout //ADC interrupt timeout
setTipPWM(0); setTipPWM(0);