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
 
@@ -142,7 +142,7 @@ SYSTEM_BUILD_DIR = $(BUILD_DIR)/system
 
#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
display.c
Show inline comments
 
@@ -8,14 +8,14 @@
 
#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)
 
@@ -24,9 +24,9 @@ uint8_t sw_right_last = 0;
 
#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)
 
{
 
@@ -505,8 +505,8 @@ void display_process(therm_settings_t* s
 
}
 

	
 

	
 
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) { 
gpio.c
Show inline comments
 
@@ -36,7 +36,7 @@ void user_input_signed(int16_t* to_modif
 
}
 

	
 

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

	
 
  GPIO_InitTypeDef GPIO_InitStruct;
 

	
gpio.h
Show inline comments
 
@@ -10,7 +10,7 @@
 

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

	
 
#endif
 

	
main.c
Show inline comments
 
@@ -23,29 +23,21 @@ 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();
 
@@ -60,7 +52,7 @@ int main(void)
 
        bootloader_enter(); 
 
 
    // Init SPI busses
 
    init_spi();
 
    spi_init();
 
 
    // Init OLED over SPI
 
    ssd1306_Init();
 
@@ -189,7 +181,7 @@ void process()
 
    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
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;
 
@@ -20,4 +20,9 @@ void init_spi()
 
    HAL_SPI_Init(&hspi1);
 
}    
 
    
 
SPI_HandleTypeDef* spi_get()
 
{
 
    return &hspi1;
 
}
 

	
 
// vim:softtabstop=4 shiftwidth=4 expandtab 
spi.h
Show inline comments
 
@@ -3,7 +3,8 @@
 

	
 
#include "stm32f0xx_hal_conf.h"
 

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

	
 
#endif
 

	
ssd1306.c
Show inline comments
 
@@ -62,7 +62,7 @@ void ssd1306_Init(void)
 
 
 
// 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
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
 
 
@@ -40,12 +5,6 @@
 
 extern "C" {
 
#endif 
 
 
/* Includes ------------------------------------------------------------------*/
 
/* Exported types ------------------------------------------------------------*/
 
/* Exported constants --------------------------------------------------------*/
 
/* Exported macro ------------------------------------------------------------*/
 
/* Exported functions ------------------------------------------------------- */
 
 
void USB_IRQHandler(void);
 
void SysTick_Handler(void);
 
 
@@ -54,5 +13,3 @@ void SysTick_Handler(void);
 
#endif
 
 
#endif /* __STM32F0xx_IT_H */
 
 
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
system/syslib.c
Show inline comments
 
@@ -62,7 +62,7 @@ void bootloader_enter(void) {
 

	
 

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

	
 
  RCC_OscInitTypeDef RCC_OscInitStruct;
system/syslib.h
Show inline comments
 
@@ -3,6 +3,6 @@
 

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

	
 
#endif
system/usbd_conf.c
Show inline comments
 
@@ -53,7 +53,7 @@ PCD_HandleTypeDef hpcd_USB_FS;
 
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)
 
@@ -502,7 +502,7 @@ void USBD_static_free(void *p)
 
  */
 
static void SystemClockConfig_Resume(void)
 
{
 
	systemclock_config();
 
	systemclock_init();
 
}
 
/* USER CODE END 4 */
 
0 comments (0 inline, 0 general)