Changeset - c14060ecae42
[Not reviewed]
cortex-f0
0 2 0
Ethan Zonca - 10 years ago 2015-01-24 16:19:18
ez@ethanzonca.com
Added initial prototype of jump-to-bootloader
2 files changed with 38 insertions and 2 deletions:
0 comments (0 inline, 0 general)
main.c
Show inline comments
 
#include "stm32f0xx_hal.h"
 
 
#include "config.h"
 
#include "ssd1306.h"
 
#include "eeprom_min.h"
 
#include "gpio.h"
 
#include "spi.h"
 
#include "stringhelpers.h"
 
 
#include "usb_device.h"
 
#include "usbd_cdc_if.h"
 
 
 
// Prototypes
 
// Move to header file
 
void process();
 
void machine();
 
void restore_settings();
 
void save_settings();
 
void save_setpoints();
 
void SystemClock_Config(void);
 
 
///////////////////////
 
enum tempunits {
 
    TEMP_UNITS_CELSIUS = 0,
 
    TEMP_UNITS_FAHRENHEIT,
 
};
 
 
// State definition
 
enum state {
 
    STATE_IDLE = 0,
 
 
    STATE_SETP,
 
    STATE_SETI,
 
    STATE_SETD,
 
    STATE_SETSTEPS,
 
    STATE_SETWINDUP,
 
    STATE_SETBOOTTOBREW,
 
    STATE_SETUNITS,
 
 
    STATE_PREHEAT_BREW,
 
    STATE_MAINTAIN_BREW,
 
    STATE_PREHEAT_STEAM,
 
    STATE_MAINTAIN_STEAM,
 
 
    STATE_TC_ERROR
 
};
 
 
uint8_t state = STATE_IDLE;
 
 
 
// Globalish setting vars
 
uint8_t boottobrew = 0;
 
uint8_t temp_units = TEMP_UNITS_CELSIUS;
 
uint16_t windup_guard = 1;
 
uint16_t k_p = 1;
 
uint16_t k_i = 1;
 
uint16_t k_d = 1;
 
uint8_t ignore_tc_error  = 0;
 
int16_t setpoint_brew = 0;
 
int16_t setpoint_steam = 0;
 
 
SPI_HandleTypeDef hspi1;
 
 
static __IO uint32_t TimingDelay;
 
 
 
 
void deinit(void)
 
{
 
    HAL_DeInit();
 
}
 
 
volatile int i=0;
 
int main(void)
 
{
 
 
    /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
 
    HAL_Init();
 
 
    /* Configure the system clock */
 
    SystemClock_Config();
 
 
    /* Initialize all configured peripherals */
 
    init_gpio();
 
    MX_USB_DEVICE_Init();
 
 
    // USB startup delay
 
    HAL_Delay(1000);
 
    HAL_GPIO_WritePin(LED_POWER, 1);
 
 
 
    /// BEGIN IMPORT/////////////////////////////////////////
 
    
 
    // TODO: Awesome pwm of power LED 
 
 
    // Configure 1ms SysTick (change if more temporal resolution needed) 
 
    //RCC_ClocksTypeDef RCC_Clocks;
 
    //RCC_GetClocksFreq(&RCC_Clocks);
 
    //SysTick_Config(RCC_Clocks.HCLK_Frequency / 1000);
 
 
    // Init SPI busses
 
    init_spi();
 
 
    // Init OLED over SPI
 
    ssd1306_Init();
 
    ssd1306_clearscreen();
 
 
    // Startup screen 
 
    ssd1306_DrawString("therm v0.1", 1, 40);
 
    ssd1306_DrawString("protofusion.org/therm", 3, 0);
 
 
    HAL_Delay(1500);
 
    ssd1306_clearscreen();
 
    
 
    restore_settings();
 
    if(boottobrew)
 
      state = STATE_PREHEAT_BREW; // Go to brew instead of idle if configured thusly
 
 
 
    // Main loop
 
    while(1)
 
    {
 
        // Process sensor inputs
 
        process();
 
 
        // Run state machine
 
        machine(); 
 
    }
 
 
/* OLD MAIN 
 
 
    for (;;) {
 
 
	CDC_Transmit_FS("a", 1); //sizeof(str)); for(count=0; count<32000000; count++); //#endif
 
        HAL_Delay(300);
 
    }
 
*/
 
 
}
 
 
/** System Clock Configuration
 
*/
 
void SystemClock_Config(void)
 
{
 
 
  RCC_OscInitTypeDef RCC_OscInitStruct;
 
  RCC_ClkInitTypeDef RCC_ClkInitStruct;
 
  RCC_PeriphCLKInitTypeDef PeriphClkInit;
 
 
  RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48;
 
  RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
 
  RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
 
  HAL_RCC_OscConfig(&RCC_OscInitStruct);
 
 
  RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK;
 
  RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI48;
 
  RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
 
  RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
 
  HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1);
 
 
  PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB;
 
  PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
 
  HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
 
 
  __SYSCFG_CLK_ENABLE();
 
 
}
 
@@ -426,194 +429,203 @@ void restore_settings()
 
    while(Minimal_FLASH_GetStatus()==FLASH_BUSY);
 
    k_p = (*(__IO uint32_t*)(EEPROM_BASE_ADDR + EEPROM_ADDR_K_P));
 
 
    while(Minimal_FLASH_GetStatus()==FLASH_BUSY);
 
    k_i = (*(__IO uint32_t*)(EEPROM_BASE_ADDR + EEPROM_ADDR_K_I));
 
 
    while(Minimal_FLASH_GetStatus()==FLASH_BUSY);
 
    k_d = (*(__IO uint32_t*)(EEPROM_BASE_ADDR + EEPROM_ADDR_K_D));
 
    
 
    while(Minimal_FLASH_GetStatus()==FLASH_BUSY);
 
    setpoint_brew = (*(__IO uint32_t*)(EEPROM_BASE_ADDR + EEPROM_ADDR_BREWTEMP));
 
 
    while(Minimal_FLASH_GetStatus()==FLASH_BUSY);
 
    setpoint_steam = (*(__IO uint32_t*)(EEPROM_BASE_ADDR + EEPROM_ADDR_STEAMTEMP));    
 
    while(Minimal_FLASH_GetStatus()==FLASH_BUSY);
 
    temp_units = (*(__IO uint32_t*)(EEPROM_BASE_ADDR + EEPROM_ADDR_UNITS));    
 
 
    Minimal_EEPROM_Lock(); */
 
}
 
 
int16_t last_temp = 21245;
 
 
 
///////////////////////////////////////////////////////////////////////////////////////
 
/// freaking multiple setpoint support ///
 
uint8_t step_duration[10] = {0,0,0,0,0,0,0,0,0,0};
 
int16_t step_setpoint[10] = {0,0,0,0,0,0,0,0,0,0};
 
uint8_t final_setpoint = 0;
 
 
// Multiple screens to set setpoint and duration on each screen
 
// press center to go to the next one, and press left or right or something to confirm
 
 
// When executing, complete on time AND(?) temperature. Maybe allow switching to OR via settings
 
 
////////////////////////////////////////////////////////////////////////////////////////////////
 
 
void machine()
 
{
 
    uint8_t last_state = state;
 
    
 
    uint8_t temp_changed = temp != last_temp;
 
    last_temp = temp;
 
 
    uint8_t sw_btn = !HAL_GPIO_ReadPin(SW_BTN);
 
    uint8_t sw_up = !HAL_GPIO_ReadPin(SW_UP);
 
    uint8_t sw_down = !HAL_GPIO_ReadPin(SW_DOWN);
 
    uint8_t sw_left = !HAL_GPIO_ReadPin(SW_LEFT);
 
    uint8_t sw_right = !HAL_GPIO_ReadPin(SW_RIGHT);
 
 
    switch(state)
 
    {
 
        // Idle state
 
        case STATE_IDLE:
 
        {
 
            // Write text to OLED
 
            // [ therm :: idle ]
 
            ssd1306_DrawString("therm :: idle ", 0, 40);
 
            pid_enabled = 0;
 
 
            if(temp_changed) {
 
                char tempstr[6];
 
                itoa_fp(temp, temp_frac, tempstr);
 
                ssd1306_DrawString("Temp: ", 3, 40);
 
                ssd1306_DrawString("    ", 3, 72);
 
                ssd1306_DrawString(tempstr, 3, 72);
 
            }
 
 
            ssd1306_drawlogo();
 
 
            switch(goto_mode) {
 
                case 2:
 
                {
 
                    ssd1306_DrawString("-> heat     ", 1, 40);
 
                } break;
 
 
                case 1:
 
                {
 
                    ssd1306_DrawString("-> setup    ", 1, 40);
 
                } break;
 
 
                case 0:
 
                {
 
                    ssd1306_DrawString("-> reset    ", 1, 40);
 
                } break;
 
            }
 
 
            // Button handler
 
            if(SW_BTN_PRESSED) {
 
                switch(goto_mode) {
 
                    case 2:
 
                        state = STATE_PREHEAT_BREW;
 
                        break;
 
                    case 1:
 
                        state = STATE_SETP;
 
                        break;
 
                    case 0:
 
                    {
 
                        ssd1306_clearscreen();
 
                        ssd1306_DrawString("Entering Bootloader", 1, 0);
 
                        ssd1306_DrawString("(hopefully)", 2, 0);
 
                        HAL_Delay(1000);
 
                        *((unsigned long *)0x200017F0) = 0xDEADBEEF; // 6KB STM32F042
 
                        NVIC_SystemReset();
 
 
                        state = STATE_IDLE;
 
                        break;
 
                    } break;
 
 
                    default:
 
                        state = STATE_PREHEAT_BREW;
 
                }
 
            }
 
            else if(SW_UP_PRESSED && goto_mode < 2) {
 
                goto_mode++;
 
            }
 
            else if(SW_DOWN_PRESSED && goto_mode > 0) {
 
                goto_mode--;
 
            }
 
 
 
            // Event Handler
 
            // N/A
 
 
        } break;
 
 
        case STATE_SETP:
 
        {
 
            // Write text to OLED
 
            // [ therm :: set p ]
 
            // [ p = 12         ]
 
            ssd1306_DrawString("Proportional", 0, 40);
 
            ssd1306_drawlogo();
 
 
            char tempstr[6];
 
            itoa(k_p, tempstr, 10);
 
            ssd1306_DrawString("P=", 1, 45);
 
            ssd1306_DrawString("    ", 1, 57);
 
            ssd1306_DrawString(tempstr, 1, 57);
 
 
            ssd1306_DrawString("Press to accept", 3, 40);
 
            
 
            // Button handler
 
            if(SW_BTN_PRESSED) {
 
                state = STATE_SETI;
 
            }
 
            else {
 
                user_input(&k_p);
 
            }
 
 
            // Event Handler
 
            // N/A
 
 
 
        } break;
 
 
        case STATE_SETI:
 
        {
 
            // Write text to OLED
 
            // [ therm :: set i ]
 
            // [ i = 12         ]
 
            ssd1306_DrawString("Integral", 0, 40);
 
            ssd1306_drawlogo();
 
 
            char tempstr[6];
 
            itoa(k_i, tempstr, 10);
 
            ssd1306_DrawString("I=", 1, 45);
 
            ssd1306_DrawString("    ", 1, 57);
 
            ssd1306_DrawString(tempstr, 1, 57);
 
 
            ssd1306_DrawString("Press to accept", 3, 40);
 
            
 
            // Button handler
 
            if(SW_BTN_PRESSED) {
 
                state = STATE_SETD;
 
            }
 
            else {
 
                user_input(&k_i);
 
            }
 
 
            // Event Handler
 
            // N/A
 
 
 
        } break;
 
 
        case STATE_SETD:
 
        {
 
            // Write text to OLED
 
            // [ therm :: set d ]
 
            // [ d = 12         ]
 
            ssd1306_DrawString("Derivative", 0, 40);
 
            ssd1306_drawlogo();
 
 
            char tempstr[6];
 
            itoa(k_d, tempstr, 10);
 
            ssd1306_DrawString("D=", 1, 45);
 
            ssd1306_DrawString("    ", 1, 57);
 
            ssd1306_DrawString(tempstr, 1, 57);
 
 
            ssd1306_DrawString("Press to accept", 3, 40);
 
 
            // Button handler
 
            if(SW_BTN_PRESSED) {
 
                state = STATE_SETWINDUP;
 
            }
 
            else {
startup_stm32f042x6.s
Show inline comments
 
/**
 
  ******************************************************************************
 
  * @file      startup_stm32f042x6.s
 
  * @author    MCD Application Team
 
  * @version   V2.1.0
 
  * @date      03-Oct-2014
 
  * @brief     STM32F042x4/STM32F042x6 devices vector table for Atollic TrueSTUDIO toolchain.
 
  *            This module performs:
 
  *                - Set the initial SP
 
  *                - Set the initial PC == Reset_Handler,
 
  *                - Set the vector table entries with the exceptions ISR address
 
  *                - Branches to main in the C library (which eventually
 
  *                  calls main()).
 
  *            After Reset the Cortex-M0 processor is in Thread mode,
 
  *            priority is Privileged, and the Stack is set to Main.
 
  ******************************************************************************
 
  * 
 
  * Redistribution and use in source and binary forms, with or without modification,
 
  * are permitted provided that the following conditions are met:
 
  *   1. Redistributions of source code must retain the above copyright notice,
 
  *      this list of conditions and the following disclaimer.
 
  *   2. Redistributions in binary form must reproduce the above copyright notice,
 
  *      this list of conditions and the following disclaimer in the documentation
 
  *      and/or other materials provided with the distribution.
 
  *   3. Neither the name of STMicroelectronics nor the names of its contributors
 
  *      may be used to endorse or promote products derived from this software
 
  *      without specific prior written permission.
 
  *
 
  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
 
  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
 
  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
 
  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
 
  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
 
  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
 
  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 
  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
 
  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
 
  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
  *
 
  ******************************************************************************
 
  */
 
 
  .syntax unified
 
  .cpu cortex-m0
 
  .fpu softvfp
 
  .thumb
 
 
.global g_pfnVectors
 
.global Default_Handler
 
 
/* start address for the initialization values of the .data section.
 
defined in linker script */
 
.word _sidata
 
/* start address for the .data section. defined in linker script */
 
.word _sdata
 
/* end address for the .data section. defined in linker script */
 
.word _edata
 
/* start address for the .bss section. defined in linker script */
 
.word _sbss
 
/* end address for the .bss section. defined in linker script */
 
.word _ebss
 
 
  .section .text.Reset_Handler
 
  .weak Reset_Handler
 
  .type Reset_Handler, %function
 
Reset_Handler:
 
 
  /* Bootloader jumping */
 
  ldr r0, =0x200017F0 /* address of magic token, is addr within memory range? */
 
  ldr r1, =0xDEADBEEF /* magical beef token */
 
  ldr r2, [r0, #0] /* load data from magic address */
 
  str r0, [r0, #0] /* zero data at magic address so we don't bootloop */ 
 
  cmp r2, r1 /* compare data at magic address to magic token */
 
  beq Reboot_Loader /* jump to bootloader if token match */
 
  /* End bootloader jumping */
 
 
 
  ldr   r0, =_estack
 
  mov   sp, r0          /* set stack pointer */
 
 
/* Copy the data segment initializers from flash to SRAM */
 
  movs r1, #0
 
  b LoopCopyDataInit
 
 
/* Boot into bootloader */
 
Reboot_Loader:
 
  ldr r0, =0x1FFFF6A6 /* Address of bootloader on f042 from CD00167594 pg 15 table 3 */
 
  /* This replaces ldr sp, [r0, #0] which doesn't work on m0 */
 
  // Set stack pointer
 
  ldr r1, [r0, #0]
 
  mov sp, r1
 
 
  // Branch to bootloader
 
  ldr r0, [r0, #4]
 
  bx r0
 
 
 
CopyDataInit:
 
  ldr r3, =_sidata
 
  ldr r3, [r3, r1]
 
  str r3, [r0, r1]
 
  adds r1, r1, #4
 
 
LoopCopyDataInit:
 
  ldr r0, =_sdata
 
  ldr r3, =_edata
 
  adds r2, r0, r1
 
  cmp r2, r3
 
  bcc CopyDataInit
 
  ldr r2, =_sbss
 
  b LoopFillZerobss
 
/* Zero fill the bss segment. */
 
FillZerobss:
 
  movs r3, #0
 
  str  r3, [r2]
 
  adds r2, r2, #4
 
 
 
LoopFillZerobss:
 
  ldr r3, = _ebss
 
  cmp r2, r3
 
  bcc FillZerobss
 
 
/* Call the clock system intitialization function.*/
 
  bl  SystemInit
 
/* Call static constructors */
 
  bl __libc_init_array
 
/* Call the application's entry point.*/
 
  bl main
 
 
LoopForever:
 
    b LoopForever
 
 
 
.size Reset_Handler, .-Reset_Handler
 
 
/**
 
 * @brief  This is the code that gets called when the processor receives an
 
 *         unexpected interrupt.  This simply enters an infinite loop, preserving
 
 *         the system state for examination by a debugger.
 
 *
 
 * @param  None
 
 * @retval : None
 
*/
 
    .section .text.Default_Handler,"ax",%progbits
 
Default_Handler:
 
Infinite_Loop:
 
  b Infinite_Loop
 
  .size Default_Handler, .-Default_Handler
 
/******************************************************************************
 
*
 
* The minimal vector table for a Cortex M0.  Note that the proper constructs
 
* must be placed on this to ensure that it ends up at physical address
 
* 0x0000.0000.
 
*
 
******************************************************************************/
 
   .section .isr_vector,"a",%progbits
 
  .type g_pfnVectors, %object
 
  .size g_pfnVectors, .-g_pfnVectors
 
 
 
g_pfnVectors:
 
  .word  _estack
 
  .word  Reset_Handler
 
  .word  NMI_Handler
 
  .word  HardFault_Handler
 
  .word  0
 
  .word  0
 
  .word  0
 
  .word  0
 
  .word  0
 
  .word  0
 
  .word  0
 
  .word  SVC_Handler
 
  .word  0
 
  .word  0
 
  .word  PendSV_Handler
 
  .word  SysTick_Handler
 
  .word  WWDG_IRQHandler                   /* Window WatchDog              */
 
  .word  PVD_VDDIO2_IRQHandler             /* PVD and VDDIO2 through EXTI Line detect */
 
  .word  RTC_IRQHandler                    /* RTC through the EXTI line    */
 
  .word  FLASH_IRQHandler                  /* FLASH                        */
 
  .word  RCC_CRS_IRQHandler                /* RCC and CRS                  */
 
  .word  EXTI0_1_IRQHandler                /* EXTI Line 0 and 1            */
 
  .word  EXTI2_3_IRQHandler                /* EXTI Line 2 and 3            */
 
  .word  EXTI4_15_IRQHandler               /* EXTI Line 4 to 15            */
 
  .word  TSC_IRQHandler                    /* TSC                          */
 
  .word  DMA1_Channel1_IRQHandler          /* DMA1 Channel 1               */
 
  .word  DMA1_Channel2_3_IRQHandler        /* DMA1 Channel 2 and Channel 3 */
 
  .word  DMA1_Channel4_5_IRQHandler        /* DMA1 Channel 4 and Channel 5 */
 
  .word  ADC1_IRQHandler                   /* ADC1                         */
 
  .word  TIM1_BRK_UP_TRG_COM_IRQHandler    /* TIM1 Break, Update, Trigger and Commutation */
 
  .word  TIM1_CC_IRQHandler                /* TIM1 Capture Compare         */
0 comments (0 inline, 0 general)