Changeset - da7e7cc3bb06
[Not reviewed]
cortex-f0
0 13 0
Ethan Zonca - 9 years ago 2015-11-28 13:18:08
ez@ethanzonca.com
Refactor and cleanup
13 files changed with 31 insertions and 140 deletions:
0 comments (0 inline, 0 general)
Makefile
Show inline comments
 
@@ -133,25 +133,25 @@ usb: $(USB_OBJECTS)
 
	$(MKDIR) $@
 

	
 
#######################################
 
# build the user application
 
#######################################
 

	
 
SYSTEM_BUILD_DIR = $(BUILD_DIR)/system
 

	
 
# list of user program objects
 
#OBJECTS = $(addprefix $(BUILD_DIR)/,$(notdir $(SOURCES:.c=.o)))
 
OBJECTS = $(addprefix $(BUILD_DIR)/,$(SOURCES:.c=.o))
 
# add an object for the startup code
 
OBJECTS += $(BUILD_DIR)/startup_stm32f042x6.o
 
OBJECTS += $(BUILD_DIR)/system/startup_stm32f042x6.o
 

	
 
# use the periphlib core library, plus generic ones (libc, libm, libnosys)
 
LIBS = -lstm32cube -lc -lm -lnosys
 
LDFLAGS = -T $(LD_SCRIPT) -L $(CUBELIB_BUILD_DIR) $(LIBS) $(USER_LDFLAGS)
 

	
 
$(BUILD_DIR)/$(TARGET).hex: $(BUILD_DIR)/$(TARGET).elf | $(SYSTEM_BUILD_DIR)
 
	$(OBJCOPY) -O ihex $(BUILD_DIR)/$(TARGET).elf $@
 
	$(OBJCOPY) -O binary $(BUILD_DIR)/$(TARGET).elf $(BUILD_DIR)/$(TARGET).bin
 

	
 
$(BUILD_DIR)/$(TARGET).elf: $(OBJECTS) $(USB_OBJECTS) $(CUBELIB) | $(SYSTEM_BUILD_DIR)
 
	$(CC) -o $@ $(CFLAGS) $(USER_LDFLAGS) $(OBJECTS) $(USB_OBJECTS) \
 
		-L$(CUBELIB_BUILD_DIR) -static $(LIBS) -Xlinker \
display.c
Show inline comments
 
#include "stm32f0xx_hal.h"
 
#include "ssd1306.h"
 
#include "stringhelpers.h"
 
#include "display.h"
 
#include "config.h"
 
#include "states.h"
 
#include "syslib.h"
 
#include "flash.h"
 
#include "gpio.h"
 

	
 
uint8_t goto_mode = 2;
 
static uint8_t goto_mode = 2;
 

	
 
// State machine
 
uint8_t sw_btn_last = 0;
 
uint8_t sw_up_last = 0;
 
uint8_t sw_down_last = 0;
 
uint8_t sw_left_last = 0;
 
uint8_t sw_right_last = 0;
 
static uint8_t sw_btn_last = 0;
 
static uint8_t sw_up_last = 0;
 
static uint8_t sw_down_last = 0;
 
static uint8_t sw_left_last = 0;
 
static uint8_t sw_right_last = 0;
 

	
 
#define SW_BTN_PRESSED (sw_btn_last == 0 && sw_btn == 1) // rising edge on buttonpress
 
#define SW_UP_PRESSED (sw_up_last == 0 && sw_up == 1)
 
#define SW_DOWN_PRESSED (sw_down_last == 0 && sw_down == 1)
 
#define SW_LEFT_PRESSED (sw_left_last == 0 && sw_left == 1)
 
#define SW_RIGHT_PRESSED (sw_right_last == 0 && sw_right == 1)
 

	
 

	
 
uint8_t trigger_drawsetpoint = 1;
 
static uint8_t trigger_drawsetpoint = 1;
 

	
 
int16_t last_temp = 21245;
 
static int16_t last_temp = 21245;
 

	
 
void display_process(therm_settings_t* set, therm_status_t* status)
 
{
 
    uint8_t last_state = status->state;
 
    
 
    uint8_t temp_changed = status->temp != last_temp;
 
    last_temp = status->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);
 
@@ -496,26 +496,26 @@ void display_process(therm_settings_t* s
 
        ssd1306_clearscreen();
 
    }
 

	
 
    // Last buttonpress
 
    sw_btn_last = sw_btn;
 
    sw_up_last = sw_up;
 
    sw_down_last = sw_down;
 
    sw_left_last = sw_left;
 
    sw_right_last = sw_right;
 
}
 

	
 

	
 
int32_t temp_last = 43002;
 
int32_t setpoint_last = 10023;
 
static int32_t temp_last = 43002;
 
static int32_t setpoint_last = 10023;
 
void draw_setpoint(therm_status_t* status) {
 
    // FIXME: need to do this when switching modes too
 
    if(status->temp != temp_last || trigger_drawsetpoint) { 
 
        char tempstr[3];
 
        itoa_fp(status->temp, status->temp_frac, tempstr);
 
        ssd1306_DrawStringBig("      ", 3, 0);
 
        ssd1306_DrawStringBig(tempstr, 3, 0);
 
    }
 

	
 
    if(trigger_drawsetpoint) 
 
        ssd1306_DrawStringBig(">", 3, 74);
 

	
gpio.c
Show inline comments
 
@@ -27,25 +27,25 @@ void user_input_signed(int16_t* to_modif
 
        if(!HAL_GPIO_ReadPin(SW_UP) ) {
 
            CHANGE_RESET;
 
            (*to_modify)++;
 
        }
 
        else if(!HAL_GPIO_ReadPin(SW_DOWN)) {
 
            CHANGE_RESET;
 
            (*to_modify)--;
 
        }
 
    }
 
}
 

	
 

	
 
void init_gpio(void) {
 
void gpio_init(void) {
 

	
 
  GPIO_InitTypeDef GPIO_InitStruct;
 

	
 
    /* GPIO Ports Clock Enable */
 
  __GPIOF_CLK_ENABLE();
 
  __GPIOA_CLK_ENABLE();
 
  __GPIOB_CLK_ENABLE();
 
  __SPI1_CLK_ENABLE();
 

	
 
   
 
  //////////////////
 
  // PORT F       //
gpio.h
Show inline comments
 
#ifndef GPIO_H
 
#define GPIO_H
 

	
 
#include <inttypes.h>
 

	
 
#define CHANGE_PERIOD_MS 100
 
#define CHANGE_ELAPSED (HAL_GetTick() - change_time_reset) > CHANGE_PERIOD_MS
 
#define CHANGE_RESET change_time_reset = HAL_GetTick()
 

	
 

	
 
void user_input(uint16_t* to_modify);
 
void user_input_signed(int16_t* to_modify);
 
void init_gpio(void);
 
void gpio_init(void);
 

	
 
#endif
 

	
 
// vim:softtabstop=4 shiftwidth=4 expandtab 
main.c
Show inline comments
 
@@ -14,62 +14,54 @@
 
 
#include "usb_device.h"
 
#include "usbd_cdc_if.h"
 
 
 
// Prototypes
 
void process();
 
 
therm_settings_t set;
 
therm_status_t status;
 
 
// Globalish setting vars
 
SPI_HandleTypeDef hspi1;
 
static __IO uint32_t TimingDelay;
 
 
void deinit(void)
 
{
 
    HAL_DeInit();
 
}
 
 
volatile int i=0;
 
int main(void)
 
{
 
 
    // Initialize HAL
 
    hal_init();
 
 
    // Configure the system clock
 
    systemclock_config();
 
    systemclock_init();
 
 
    // Unset bootloader option bytes (if set)
 
    void bootloader_unset(void);
 
 
    // Init GPIO
 
    init_gpio();
 
    gpio_init();
 
 
    // Init USB (TODO: Handle plugged/unplugged with external power)
 
    MX_USB_DEVICE_Init();
 
//    set.val.usb_plugged = 
 
 
    // USB startup delay
 
    HAL_Delay(1000);
 
    HAL_GPIO_WritePin(LED_POWER, 1);
 
 
    // Enter into bootloader if up button pressed on boot
 
    if(!HAL_GPIO_ReadPin(SW_UP))
 
        bootloader_enter(); 
 
 
    // Init SPI busses
 
    init_spi();
 
    spi_init();
 
 
    // Init OLED over SPI
 
    ssd1306_Init();
 
    ssd1306_clearscreen();
 
   
 
    // Default settings 
 
    set.val.boottobrew = 0;
 
    set.val.temp_units = TEMP_UNITS_CELSIUS;
 
    set.val.windup_guard = 1;
 
    set.val.k_p = 1;
 
    set.val.k_i = 1;
 
    set.val.k_d = 1;
 
@@ -180,25 +172,25 @@ void process()
 
{
 
 
    uint32_t ticks = HAL_GetTick();
 
 
    if(ticks - last_led > 400) 
 
    {
 
        last_led = ticks;
 
    }
 
 
    if((ticks - last_pid > PID_PERIOD))
 
    {
 
        #ifdef MAX31855_TC_SENSOR
 
        max31855_readtemp(&hspi1, &set, &status); // Read MAX31855
 
        max31855_readtemp(spi_get(), &set, &status); // Read MAX31855
 
        #endif
 
 
        #ifdef MAX31865_RTD_SENSOR
 
        max31865_readtemp(&set, &status);
 
        #endif
 
 
    HAL_GPIO_TogglePin(LED_POWER);
 
 
        if(status.pid_enabled) 
 
        {
 
            // Get ssr output for next time
 
            int16_t power_percent = update_pid(set.val.k_p, set.val.k_i, set.val.k_d, status.temp, status.temp_frac, status.setpoint);
spi.c
Show inline comments
 

	
 
#include "stm32f0xx_hal_conf.h"
 
#include "stm32f0xx_hal_gpio_ex.h"
 
extern SPI_HandleTypeDef hspi1;
 
SPI_HandleTypeDef hspi1;
 

	
 
void init_spi()
 
void spi_init()
 
{
 
    hspi1.Instance = SPI1;
 
    hspi1.Init.Mode = SPI_MODE_MASTER;
 
    hspi1.Init.Direction = SPI_DIRECTION_2LINES;
 
    hspi1.Init.DataSize = SPI_DATASIZE_8BIT;
 
    hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
 
    hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
 
    hspi1.Init.NSS = SPI_NSS_SOFT;
 
    hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
 
    hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
 
    hspi1.Init.TIMode = SPI_TIMODE_DISABLED;
 
    hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLED;
 
    hspi1.Init.NSSPMode = SPI_NSS_PULSE_ENABLED;
 
    HAL_SPI_Init(&hspi1);
 
}    
 
    
 
SPI_HandleTypeDef* spi_get()
 
{
 
    return &hspi1;
 
}
 

	
 
// vim:softtabstop=4 shiftwidth=4 expandtab 
spi.h
Show inline comments
 
#ifndef SPI_H
 
#define SPI_H
 

	
 
#include "stm32f0xx_hal_conf.h"
 

	
 
void init_spi();
 
void spi_init();
 
SPI_HandleTypeDef* spi_get();
 

	
 
#endif
 

	
 
// vim:softtabstop=4 shiftwidth=4 expandtab 
ssd1306.c
Show inline comments
 
@@ -53,25 +53,25 @@ void ssd1306_Init(void)
 
  WriteCommand(0xF1); //22 or F1 if not externalvcc
 
  WriteCommand(0xDB);
 
  WriteCommand(0x40);
 
  WriteCommand(0xA4); // dispalyallon_resume
 
  WriteCommand(0xA6); // normaldisplay
 
 
 
  WriteCommand(0xAF); // display on 
 
}
 
 
 
// Times New Roman font
 
const char fontData[][5] =
 
static const char fontData[][5] =
 
{                                       // Refer to "Times New Roman" Font Database
 
                                        //   Basic Characters
 
    {0x00,0x00,0x00,0x00,0x00},         //   (  0)    - 0x0020 No-Break Space
 
    {0x00,0x00,0x4F,0x00,0x00},         //   (  1)  ! - 0x0021 Exclamation Mark
 
    {0x00,0x07,0x00,0x07,0x00},         //   (  2)  " - 0x0022 Quotation Mark
 
    {0x14,0x7F,0x14,0x7F,0x14},         //   (  3)  # - 0x0023 Number Sign
 
    {0x24,0x2A,0x7F,0x2A,0x12},         //   (  4)  $ - 0x0024 Dollar Sign
 
    {0x23,0x13,0x08,0x64,0x62},         //   (  5)  % - 0x0025 Percent Sign
 
    {0x36,0x49,0x55,0x22,0x50},         //   (  6)  & - 0x0026 Ampersand
 
    {0x00,0x05,0x03,0x00,0x00},         //   (  7)  ' - 0x0027 Apostrophe
 
    {0x00,0x1C,0x22,0x41,0x00},         //   (  8)  ( - 0x0028 Left Parenthesis
 
    {0x00,0x41,0x22,0x1C,0x00},         //   (  9)  ) - 0x0029 Right Parenthesis
system/interrupts.c
Show inline comments
 
/**
 
  ******************************************************************************
 
  * @file    stm32f0xx_it.c
 
  * @date    05/12/2014 20:22:27
 
  * @brief   Interrupt Service Routines.
 
  ******************************************************************************
 
  *
 
  * COPYRIGHT(c) 2014 STMicroelectronics
 
  *
 
  * 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.
 
  *
 
  ******************************************************************************
 
  */
 
/* Includes ------------------------------------------------------------------*/
 
#include "stm32f0xx_hal.h"
 
#include "stm32f0xx.h"
 
#include "interrupts.h"
 
/* USER CODE BEGIN 0 */
 
 
/* USER CODE END 0 */
 
/* External variables --------------------------------------------------------*/
 
 
extern PCD_HandleTypeDef hpcd_USB_FS;
 
 
/******************************************************************************/
 
/*            Cortex-M0 Processor Interruption and Exception Handlers         */ 
 
/******************************************************************************/
 
 
/**
 
* @brief This function handles USB global Interrupt (combined with EXTI line 18).
 
*/
 
void USB_IRQHandler(void)
 
{
 
  /* USER CODE BEGIN USB_IRQn 0 */
 
 
  /* USER CODE END USB_IRQn 0 */
 
  HAL_PCD_IRQHandler(&hpcd_USB_FS);
 
  /* USER CODE BEGIN USB_IRQn 1 */
 
 
  /* USER CODE END USB_IRQn 1 */
 
}
 
 
/**
 
* @brief This function handles System tick timer.
 
*/
 
void SysTick_Handler(void)
 
{
 
  /* USER CODE BEGIN SysTick_IRQn 0 */
 
 
  /* USER CODE END SysTick_IRQn 0 */
 
  HAL_IncTick();
 
  HAL_SYSTICK_IRQHandler();
 
  /* USER CODE BEGIN SysTick_IRQn 1 */
 
 
  /* USER CODE END SysTick_IRQn 1 */
 
}
 
 
/* USER CODE BEGIN 1 */
 
 
/* USER CODE END 1 */
 
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
system/interrupts.h
Show inline comments
 
/**
 
  ******************************************************************************
 
  * @file    stm32f0xx_it.h
 
  * @date    05/12/2014 20:22:27
 
  * @brief   This file contains the headers of the interrupt handlers.
 
  ******************************************************************************
 
  *
 
  * COPYRIGHT(c) 2014 STMicroelectronics
 
  *
 
  * 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.
 
  *
 
  ******************************************************************************
 
  */
 
 
/* Define to prevent recursive inclusion -------------------------------------*/
 
#ifndef __STM32F0xx_IT_H
 
#define __STM32F0xx_IT_H
 
 
#ifdef __cplusplus
 
 extern "C" {
 
#endif 
 
 
/* Includes ------------------------------------------------------------------*/
 
/* Exported types ------------------------------------------------------------*/
 
/* Exported constants --------------------------------------------------------*/
 
/* Exported macro ------------------------------------------------------------*/
 
/* Exported functions ------------------------------------------------------- */
 
 
void USB_IRQHandler(void);
 
void SysTick_Handler(void);
 
 
#ifdef __cplusplus
 
}
 
#endif
 
 
#endif /* __STM32F0xx_IT_H */
 
 
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
system/syslib.c
Show inline comments
 
@@ -53,25 +53,25 @@ void bootloader_enter(void) {
 
    HAL_FLASHEx_OBErase();
 
  
 
    HAL_FLASHEx_OBProgram(&OBParam);
 
  
 
    HAL_FLASH_OB_Lock();
 
    HAL_FLASH_Lock();
 
  
 
    HAL_FLASH_OB_Launch();
 
}
 

	
 

	
 
// Clock configuration
 
void systemclock_config(void)
 
void systemclock_init(void)
 
{
 

	
 
  RCC_OscInitTypeDef RCC_OscInitStruct;
 
  RCC_ClkInitTypeDef RCC_ClkInitStruct;
 
  RCC_PeriphCLKInitTypeDef PeriphClkInit;
 

	
 
  // Enable HSI48 for main system clock
 
  RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48|RCC_OSCILLATORTYPE_HSI14;
 
  RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
 
  RCC_OscInitStruct.HSI14State = RCC_HSI14_ON;
 
  RCC_OscInitStruct.HSI14CalibrationValue = 16;
 
  RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
system/syslib.h
Show inline comments
 
#ifndef BOOTLIB_H
 
#define BOOTLIB_H
 

	
 
void bootloader_unset(void);
 
void bootloader_enter(void);
 
void systemclock_config(void);
 
void systemclock_init(void);
 

	
 
#endif
system/usbd_conf.c
Show inline comments
 
@@ -44,25 +44,25 @@
 
PCD_HandleTypeDef hpcd_USB_FS;
 
 
/* USER CODE BEGIN 0 */
 
__IO uint32_t remotewakeupon=0;
 
/* USER CODE END 0 */
 
 
/* Private function prototypes -----------------------------------------------*/
 
/* Private functions ---------------------------------------------------------*/
 
/* USER CODE BEGIN 1 */
 
static void SystemClockConfig_Resume(void);
 
/* USER CODE END 1 */
 
void HAL_PCDEx_SetConnectionState(PCD_HandleTypeDef *hpcd, uint8_t state);
 
extern void systemclock_config(void);
 
extern void systemclock_init(void);
 
 
/*******************************************************************************
 
		       LL Driver Callbacks (PCD -> USB Device Library)
 
*******************************************************************************/
 
/* MSP Init */
 
 
void HAL_PCD_MspInit(PCD_HandleTypeDef* hpcd)
 
{
 
  if(hpcd->Instance==USB)
 
  {
 
  /* USER CODE BEGIN USB_MspInit 0 */
 
 
@@ -493,25 +493,25 @@ void USBD_static_free(void *p)
 
 
}
 
 
/* USER CODE BEGIN 4 */
 
/**
 
  * @brief  Configures system clock after wake-up from USB Resume CallBack:
 
  *         enable HSI, PLL and select PLL as system clock source.
 
  * @param  None
 
  * @retval None
 
  */
 
static void SystemClockConfig_Resume(void)
 
{
 
	systemclock_config();
 
	systemclock_init();
 
}
 
/* USER CODE END 4 */
 
 
/**
 
* @brief Software Device Connection
 
* @param hpcd: PCD handle
 
* @param state: connection state (0 : disconnected / 1: connected)
 
* @retval None
 
*/
 
void HAL_PCDEx_SetConnectionState(PCD_HandleTypeDef *hpcd, uint8_t state)
 
{
 
/* USER CODE BEGIN 5 */
0 comments (0 inline, 0 general)