fixed folder structure, added v0 KiCad

This commit is contained in:
2024-12-17 17:10:30 +01:00
parent 044fb7c661
commit ff59809915
241 changed files with 429553 additions and 0 deletions

View File

@ -0,0 +1,82 @@
/**
* @file HTPA_32x32d.h
* @brief Header for HTPA 32x32d infrared array sensor library
* @author Tim-Erik Düntzsch t.duentzsch@fasttube.de
*
* @date 25.03.2023 - first implementation (untested)
*
* @todo finish HTPA_ReadBlock function
* @todo add calibration function
* @todo add temperature conversion function
*
* @test communication and readout
*
* @version 0.1
*/
#include <stdbool.h>
#ifndef INC_HTPA_32X32D_H_
#define INC_HTPA_32X32D_H_
#define ReadToFromTable
// ToDo: Sensor selection / add shortened lookup tables for selection:
#define HTPA32x32dL2_1HiSiF5_0_Gain3k3
//#define HTPA32x32dR1L2_1HiSiF5_0_Gain3k3_Extended
#ifdef HTPA32x32dL2_1HiSiF5_0_Gain3k3
#define TABLENUMBER 114
#define PCSCALEVAL 100000000 //327000000000 //PixelConst scale value for table... lower 'L' for (long)
#define NROFTAELEMENTS 7
#define NROFADELEMENTS 180 //because of shortened lookup table (capped at 300°C) //1595 default (~930°C)
#define TAEQUIDISTANCE 100 //dK
#define ADEQUIDISTANCE 64 //dig
#define ADEXPBITS 6 //2^ADEXPBITS=ADEQUIDISTANCE
#define TABLEOFFSET 1024
#define EQUIADTABLE //if defined, ADELEMENTS have to be 2^N quantizied! else more CPU Power is needed
#ifdef EQUIADTABLE
#undef FLOATTABLE
#endif
#define MBITTRIMDefault 0x2C //use REF_CAL=2 here. Table does not match, so GlobalGain ist set to 50 % to compensate this.
#define SensRv 1 //Sensor Revision is set to 1 (Redesign)
#endif
#ifdef HTPA32x32dR1L2_1HiSiF5_0_Gain3k3_Extended
#define TABLENUMBER 114
#define PCSCALEVAL 100000000 //327000000000 //PixelConst scale value for table... lower 'L' for (long)
#define NROFTAELEMENTS 12
#define NROFADELEMENTS 1595 //130 possible due to Program memory, higher values possible if NROFTAELEMENTS is decreased
#define TAEQUIDISTANCE 100 //dK
#define ADEQUIDISTANCE 64 //dig
#define ADEXPBITS 6 //2^ADEXPBITS=ADEQUIDISTANCE
#define TABLEOFFSET 1792
#define EQUIADTABLE //if defined, ADELEMENTS have to be 2^N quantizied! else more CPU Power is needed
#ifdef EQUIADTABLE
#undef FLOATTABLE
#endif
#define MBITTRIMDefault 0x2C
#define SensRv 1
#endif
/// @brief HTPA status register struct
typedef struct {
uint8_t block; // currently selected block
bool vdd_meas; // selection whether first two bytes are VDD or PTA
bool blind;
bool eoc; // end of conversion flag
} HTPA_Status;
void HTPA_Init(I2C_HandleTypeDef *hi2c);
void HTPA_ReadSensor(uint32_t dataArray[32]);
uint8_t HTPA_ReadEEPROM_byte(uint16_t address);
void HTPA_WriteRegister(uint8_t address, uint8_t byte);
void HTPA_ReadRegister(uint8_t address, uint8_t* pData, uint16_t length);
void HTPA_GetStatus(void);
uint32_t HTPA_calcPowerTwo(uint8_t power);
#endif /* INC_HTPA_32X32D_H_ */

File diff suppressed because one or more lines are too long

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

71
Software/Core/Inc/main.h Normal file
View File

@ -0,0 +1,71 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.h
* @brief : Header for main.c file.
* This file contains the common defines of the application.
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f0xx_hal.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void Error_Handler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
#define LED_Pin GPIO_PIN_3
#define LED_GPIO_Port GPIOA
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
#ifdef __cplusplus
}
#endif
#endif /* __MAIN_H */

View File

@ -0,0 +1,322 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f0xx_hal_conf.h
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* Copyright (c) 2016 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F0xx_HAL_CONF_H
#define __STM32F0xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
/*#define HAL_ADC_MODULE_ENABLED */
/*#define HAL_CRYP_MODULE_ENABLED */
#define HAL_CAN_MODULE_ENABLED
/*#define HAL_CEC_MODULE_ENABLED */
/*#define HAL_COMP_MODULE_ENABLED */
/*#define HAL_CRC_MODULE_ENABLED */
/*#define HAL_CRYP_MODULE_ENABLED */
/*#define HAL_TSC_MODULE_ENABLED */
/*#define HAL_DAC_MODULE_ENABLED */
/*#define HAL_I2S_MODULE_ENABLED */
/*#define HAL_IWDG_MODULE_ENABLED */
/*#define HAL_LCD_MODULE_ENABLED */
/*#define HAL_LPTIM_MODULE_ENABLED */
/*#define HAL_RNG_MODULE_ENABLED */
/*#define HAL_RTC_MODULE_ENABLED */
/*#define HAL_SPI_MODULE_ENABLED */
/*#define HAL_TIM_MODULE_ENABLED */
/*#define HAL_UART_MODULE_ENABLED */
/*#define HAL_USART_MODULE_ENABLED */
/*#define HAL_IRDA_MODULE_ENABLED */
/*#define HAL_SMARTCARD_MODULE_ENABLED */
/*#define HAL_SMBUS_MODULE_ENABLED */
/*#define HAL_WWDG_MODULE_ENABLED */
/*#define HAL_PCD_MODULE_ENABLED */
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
/* ########################## HSE/HSI Values adaptation ##################### */
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)16000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
/**
* @brief In the following line adjust the External High Speed oscillator (HSE) Startup
* Timeout value
*/
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief In the following line adjust the Internal High Speed oscillator (HSI) Startup
* Timeout value
*/
#if !defined (HSI_STARTUP_TIMEOUT)
#define HSI_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSI start up */
#endif /* HSI_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator for ADC (HSI14) value.
*/
#if !defined (HSI14_VALUE)
#define HSI14_VALUE ((uint32_t)14000000) /*!< Value of the Internal High Speed oscillator for ADC in Hz.
The real value may vary depending on the variations
in voltage and temperature. */
#endif /* HSI14_VALUE */
/**
* @brief Internal High Speed oscillator for USB (HSI48) value.
*/
#if !defined (HSI48_VALUE)
#define HSI48_VALUE ((uint32_t)48000000) /*!< Value of the Internal High Speed oscillator for USB in Hz.
The real value may vary depending on the variations
in voltage and temperature. */
#endif /* HSI48_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE ((uint32_t)40000)
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature. */
/**
* @brief External Low Speed oscillator (LSI) value.
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */
/**
* @brief Time out for LSE start up value in ms.
*/
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)3) /*!< tick interrupt priority (lowest by default) */
/* Warning: Must be set to higher priority for HAL_Delay() */
/* and HAL_GetTick() usage under interrupt context */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
#define INSTRUCTION_CACHE_ENABLE 0
#define DATA_CACHE_ENABLE 0
#define USE_SPI_CRC 0U
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
#define USE_HAL_TSC_REGISTER_CALLBACKS 0U /* TSC register callback disabled */
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f0xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f0xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32f0xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f0xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f0xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f0xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f0xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f0xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32f0xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f0xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f0xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f0xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f0xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f0xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f0xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f0xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f0xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f0xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f0xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f0xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32f0xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f0xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f0xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32f0xx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f0xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f0xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f0xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F0xx_HAL_CONF_H */

View File

@ -0,0 +1,62 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f0xx_it.h
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F0xx_IT_H
#define __STM32F0xx_IT_H
#ifdef __cplusplus
extern "C" {
#endif
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void NMI_Handler(void);
void HardFault_Handler(void);
void SVC_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F0xx_IT_H */

View File

@ -0,0 +1,15 @@
/**
* @file tire_data.h
* @brief Tire data for calibration of HTPA sensor
* @author Tim-Erik Düntzsch t.duentzsch@fasttube.de
*
* @date 27.03.2023 - first implementation (untested)
*/
#ifndef INC_TIRE_DATA_H_
#define INC_TIRE_DATA_H_
uint8_t epsilon = 94; // emissivity of 0.94 (tire rubber)
#endif /* INC_TIRE_DATA_H_ */

55
Software/Core/Inc/tts.h Normal file
View File

@ -0,0 +1,55 @@
/*
* tts.h
*
* Created on: Jun 29, 2024
* Author: ted
*/
#ifndef INC_TTS_H_
#define INC_TTS_H_
#include "main.h"
typedef enum {
TTS_FL,
TTS_FR,
TTS_RL,
TTS_RR
} TTS_SensorID;
typedef enum {
FT20e = 20, // "lol" - TEDü
FT20c = 21,
FT22,
FT23,
FT24
} TTS_CarID;
typedef enum {
UNKNOWN,
OZ7_SLICKS,
OZ7_RAIN,
JP8_SLICKS
} TTS_TireID;
typedef struct {
TTS_TireID id; // Tire ID
uint8_t epsilon; // Emissivity [%]
uint8_t outerLeftStart; // First pixel of outer left zone
uint8_t outerLeftStop; // Last pixel of outer right zone
uint8_t centerLeftStart;
uint8_t centerLeftStop;
uint8_t centerStart;
uint8_t centerStop;
uint8_t centerRightStart;
uint8_t centerRightStop;
uint8_t outerRightStart;
uint8_t outerRightStop;
} TTS_TireData;
void TTS_Init(CAN_HandleTypeDef *hcan);
void TTS_LoadTireData(void);
void TTS_SendCAN(uint32_t tireZones[5]);
void TTS_TireZones(uint32_t tempArray[32], uint32_t tireTempArray[5]);
#endif /* INC_TTS_H_ */

View File

@ -0,0 +1,384 @@
/**
* @file HTPA_32x32d.c
* @brief Library for HTPA 32x32d infrared array sensor
* @author Tim-Erik Düntzsch t.duentzsch@fasttube.de
*
* @date 08.03.2024 - successful readout of block 3 top half and conversion factors
*
* @test eeprom readout and temperature conversion
*
* @version 0.7
*/
#include <stdbool.h>
#include <math.h>
#include "main.h"
#include "HTPA_32x32d.h"
#include "HTPA_lookuptable_short-300degC.h"
// I2C address
#define HTPA_SENSOR_ADDRESS 0x1A
#define HTPA_EEPROM_ADDRESS 0x50
// Sensor configuration registers (write only)
#define HTPA_SENSOR_CONFIG 0x01 // Configuration register
#define HTPA_SENSOR_TRIM_1 0x03 // Amplification and ADC resolution
#define HTPA_SENSOR_TRIM_2 0x04 // Bias current of Top ADC
#define HTPA_SENSOR_TRIM_3 0x05 // Bias current of Bot ADC
#define HTPA_SENSOR_TRIM_4 0x06 // Clock frequency
#define HTPA_SENSOR_TRIM_5 0x07 // Common mode voltage preamplifier top
#define HTPA_SENSOR_TRIM_6 0x08 // Common mode voltage preamplifier bot
#define HTPA_SENSOR_TRIM_7 0x09 // Internal pull-ups SDA, SCL
// Sensor read only registers
#define HTPA_SENSOR_STATUS 0x02 // Status register
#define HTPA_SENSOR_READTOP 0x0A // Read top half
#define HTPA_SENSOR_READBOT 0x0B // Read bot half
// EEPROM addresses
#define HTPA_EEPROM_VDDCOMPGRAD 0x0340 // Start address for vddcompgrad[i][j]
#define HTPA_EEPROM_VDDCOMPOFF 0x0540 // Start address for vddcompoff[i][j]
#define HTPA_EEPROM_THGRAD 0x0A40 // Start address for thgrad[i][j] (top, block3, pixel 384 -> 0x0740 + 2*384 = 0x0A40
#define HTPA_EEPROM_THOFFSET 0x1240 // Start address for thoffset[i][j] (top, block3, pixel 384 -> 0x0F40 + 2*384 = 0x1240
#define HTPA_EEPROM_PI 0x1A40 // Start address for pij[i][j] (top, block3, pixel 384 -> 0x1740 + 2*384 = 0x1A40
#define HTPA_ROWSELECTION 3u // select which row of block 3 is used for temperature calculation (0-3)
#define HTPA_CUSTOM_EPSILON 84u
// I2C transmit delay
#define HTPA_I2C_MAX_DELAY 0xFF
I2C_HandleTypeDef* htpa_hi2c; // pointer to i2c handle
// EEPROM data:
uint8_t gradscale, vddscgrad, vddscoff, epsilon, arraytype, nrofdefpix;
int8_t globaloff;
uint16_t vddth1, vddth2, ptatth1, ptatth2, globalgain, tablenumber;
uint16_t pij[32];
int16_t thgrad[32];
int16_t thoffset[32];
int16_t vddcompgrad[32];
int16_t vddcompoff[32];
float pixcmin, pixcmax, ptatgr, ptatoff;
// Sensor data:
HTPA_Status htpa_statusReg;
uint8_t data_topBlock[258];
uint8_t elOffset_topBlock[258];
uint16_t vdd_topBlock, ptat_topBlock;
uint16_t pixel_topBlock[32];
uint16_t elOffset[32];
// Calculated values:
uint32_t gradscale_div, vddscgrad_div, vddscoff_div;
int32_t pixcij[32]; // sensitivity coefficients per pixel (needed for 11.5)
int32_t vij_comp[32]; // thermal offset compensated (11.2)
int32_t vij_comp_s[32]; // electrical offset compensated (11.3)
int32_t vij_vddcomp[32]; // vdd compensated (11.4)
int32_t vij_pixc[32]; // sensitivity coefficients applied (11.5)
uint32_t temp_pix[32]; // final pixel temperature in dK (11.7)
float ambient_temperature;
/**
* @brief Initialization of HTPA Sensor
*
* Sets the wakeup bit in the status register and writes the desired sensor
* configuration to the respective registers.
* Afterwards the sensor is in idle and ready for conversion.
*
* @param *hi2c: Pointer to I2C Handle
*/
void HTPA_Init(I2C_HandleTypeDef *hi2c){
htpa_hi2c = hi2c;
// I2C initialized on 400kbit Fast Mode
/*
* Read EEPROM calibration values
* (see datasheet Figure 13)
*/
uint8_t eeprom_float[4] = {0};
eeprom_float[0] = HTPA_ReadEEPROM_byte(0x0000);
eeprom_float[1] = HTPA_ReadEEPROM_byte(0x0001);
eeprom_float[2] = HTPA_ReadEEPROM_byte(0x0002);
eeprom_float[3] = HTPA_ReadEEPROM_byte(0x0003);
pixcmin = *(float*)eeprom_float;
eeprom_float[0] = HTPA_ReadEEPROM_byte(0x0004);
eeprom_float[1] = HTPA_ReadEEPROM_byte(0x0005);
eeprom_float[2] = HTPA_ReadEEPROM_byte(0x0006);
eeprom_float[3] = HTPA_ReadEEPROM_byte(0x0007);
pixcmax = *(float*)eeprom_float;
gradscale = HTPA_ReadEEPROM_byte(0x0008);
tablenumber = HTPA_ReadEEPROM_byte(0x000C) << 8 | HTPA_ReadEEPROM_byte(0x000B);
epsilon = HTPA_ReadEEPROM_byte(0x000D);
arraytype = HTPA_ReadEEPROM_byte(0x0022);
vddth1 = HTPA_ReadEEPROM_byte(0x0027) << 8 | HTPA_ReadEEPROM_byte(0x0026);
vddth2 = HTPA_ReadEEPROM_byte(0x0029) << 8 | HTPA_ReadEEPROM_byte(0x0028);
eeprom_float[0] = HTPA_ReadEEPROM_byte(0x0034);
eeprom_float[1] = HTPA_ReadEEPROM_byte(0x0035);
eeprom_float[2] = HTPA_ReadEEPROM_byte(0x0036);
eeprom_float[3] = HTPA_ReadEEPROM_byte(0x0037);
ptatgr = *(float*)eeprom_float;
eeprom_float[0] = HTPA_ReadEEPROM_byte(0x0038);
eeprom_float[1] = HTPA_ReadEEPROM_byte(0x0039);
eeprom_float[2] = HTPA_ReadEEPROM_byte(0x003A);
eeprom_float[3] = HTPA_ReadEEPROM_byte(0x003B);
ptatoff = *(float*)eeprom_float;
ptatth1 = HTPA_ReadEEPROM_byte(0x003D) << 8 | HTPA_ReadEEPROM_byte(0x003C);
ptatth2 = HTPA_ReadEEPROM_byte(0x003F) << 8 | HTPA_ReadEEPROM_byte(0x003E);
vddscgrad = HTPA_ReadEEPROM_byte(0x004E);
vddscoff = HTPA_ReadEEPROM_byte(0x004F);
globaloff = HTPA_ReadEEPROM_byte(0x0054);
globalgain = HTPA_ReadEEPROM_byte(0x0056) << 8 | HTPA_ReadEEPROM_byte(0x0055);
nrofdefpix = HTPA_ReadEEPROM_byte(0x007F);
for(uint8_t i = 0; i < 32; i++) {
// start at top half, row 4
vddcompgrad[i] = HTPA_ReadEEPROM_byte(HTPA_EEPROM_VDDCOMPGRAD + HTPA_ROWSELECTION * 64 + 2 * i + 1) << 8 | HTPA_ReadEEPROM_byte(HTPA_EEPROM_VDDCOMPGRAD + HTPA_ROWSELECTION * 64 + 2 * i);
// ignore bottom half
}
for(uint8_t i = 0; i < 32; i++) {
// start at top half, row 4
vddcompoff[i] = HTPA_ReadEEPROM_byte(HTPA_EEPROM_VDDCOMPOFF + HTPA_ROWSELECTION * 64 + 2 * i + 1) << 8 | HTPA_ReadEEPROM_byte(HTPA_EEPROM_VDDCOMPOFF + HTPA_ROWSELECTION * 64 + 2 * i);
// ignore bottom half
}
for(uint8_t i = 0; i < 32; i++) {
// start at block 3, row 4 (pixel 480)
thgrad[i] = HTPA_ReadEEPROM_byte(HTPA_EEPROM_THGRAD + HTPA_ROWSELECTION * 64 + 2 * i + 1) << 8 | HTPA_ReadEEPROM_byte(HTPA_EEPROM_THGRAD + HTPA_ROWSELECTION * 64 + 2 * i);
// ignore bottom half
}
for(uint8_t i = 0; i < 32; i++) {
// start at block 3, row 4 (pixel 480)
thoffset[i] = HTPA_ReadEEPROM_byte(HTPA_EEPROM_THOFFSET + HTPA_ROWSELECTION * 64 + 2 * i + 1) << 8 | HTPA_ReadEEPROM_byte(HTPA_EEPROM_THOFFSET + HTPA_ROWSELECTION * 64 + 2 * i);
// ignore bottom half
}
for(uint8_t i = 0; i < 32; i++) {
// start at block 3, row 4 (pixel 480)
pij[i] = HTPA_ReadEEPROM_byte(HTPA_EEPROM_PI + HTPA_ROWSELECTION * 64 + 2 * i + 1) << 8 | HTPA_ReadEEPROM_byte(HTPA_EEPROM_PI + HTPA_ROWSELECTION * 64 + 2 * i);
// ignore bottom half
}
/* Set I2C to Fast Mode Plus (1Mbit) for sensor readout: */
if (HAL_I2C_DeInit(htpa_hi2c) != HAL_OK)
{
Error_Handler();
}
htpa_hi2c->Init.Timing = 0x00000107;
if (HAL_I2C_Init(htpa_hi2c) != HAL_OK)
{
Error_Handler();
}
__HAL_SYSCFG_FASTMODEPLUS_ENABLE(I2C_FASTMODEPLUS_I2C1);
HAL_Delay(100);
/*
* Write sensor calibration registers
*/
HTPA_WriteRegister(HTPA_SENSOR_CONFIG, 0x01); // wakeup
HAL_Delay(10);
HTPA_WriteRegister(HTPA_SENSOR_TRIM_1, 0x0C); // bit 5,4 = 00 -> amplification = 0, bit 3-0 = 1100 -> 16bit ADC-Resolution (4 + m=12)
HAL_Delay(10);
HTPA_WriteRegister(HTPA_SENSOR_TRIM_2, 0x0C);
HAL_Delay(10);
HTPA_WriteRegister(HTPA_SENSOR_TRIM_3, 0x0C);
HAL_Delay(10);
HTPA_WriteRegister(HTPA_SENSOR_TRIM_4, 0x14); // clock frequency set to 0x14 -> 4.75MHz -> time for quarter frame: ~27ms
HAL_Delay(10);
HTPA_WriteRegister(HTPA_SENSOR_TRIM_5, 0x0C);
HAL_Delay(10);
HTPA_WriteRegister(HTPA_SENSOR_TRIM_6, 0x0C);
HAL_Delay(10);
HTPA_WriteRegister(HTPA_SENSOR_TRIM_7, 0x88);
HAL_Delay(10);
//HTPA_WriteRegister(HTPA_SENSOR_CONFIG, 0x09); // start sensor
//HAL_Delay(10);
/*
* Calculations
*/
//gradscale_div = HTPA_calcPowerTwo(gradscale);
gradscale_div = HTPA_calcPowerTwo(gradscale);
vddscgrad_div = HTPA_calcPowerTwo(vddscgrad);
vddscoff_div = HTPA_calcPowerTwo(vddscoff);
// calculate sensitivity coefficients: (datasheet 11.5)
for(uint8_t i = 0; i < 32; i++) {
pixcij[i] = (int32_t)pixcmax - (int32_t)pixcmin;
pixcij[i] = pixcij[i] / 65535;
pixcij[i] = pixcij[i] * pij[i];
pixcij[i] = pixcij[i] + pixcmin;
pixcij[i] = pixcij[i] * 1.0 * HTPA_CUSTOM_EPSILON / 100;
pixcij[i] = pixcij[i] * 1.0 * globalgain / 10000;
}
}
uint32_t HTPA_calcPowerTwo(uint8_t power) {
if (power == 0)
return 1;
else if ((power % 2) == 0)
return HTPA_calcPowerTwo(power / 2) * HTPA_calcPowerTwo(power / 2);
else
return 2 * HTPA_calcPowerTwo(power / 2) * HTPA_calcPowerTwo(power / 2);
}
void HTPA_ReadSensor(uint32_t dataArray[32]) {
uint8_t config = 0;
/*
* Read top array half of block3 with PTAT
*/
// write block and vdd/ptat selection to config register:
config |= (3 << 4); // bit 5,4 block 3 selection
config |= 0x09; // bit 3 start | bit 0 wakeup
HTPA_WriteRegister(HTPA_SENSOR_CONFIG, config);
HAL_Delay(30); // conversion around 27ms in standard config
HTPA_GetStatus();
while(htpa_statusReg.eoc != 1) {
HAL_Delay(1);
HTPA_GetStatus();
} // wait until eoc flag is set then read register data
HTPA_ReadRegister(HTPA_SENSOR_READTOP, data_topBlock, 258);
ptat_topBlock = (data_topBlock[0] << 8) | data_topBlock[1];
/*
* Read electrical offset with VDD
*/
config |= 0x04; // bit 2 vdd_meas
config |= 0x02; // bit 1 blind for electrical offset readout (block selection is ignored)
HTPA_WriteRegister(HTPA_SENSOR_CONFIG, config);
HAL_Delay(30); // conversion around 27ms in standard config
while(htpa_statusReg.eoc != 1) {
HAL_Delay(1);
HTPA_GetStatus();
} // wait until eoc flag is set then read register data
HTPA_ReadRegister(HTPA_SENSOR_READTOP, elOffset_topBlock, 258);
vdd_topBlock = (elOffset_topBlock[0] << 8) | elOffset_topBlock[1];
/*
* Sort sensor data and assign to pixels
*/
for(int i=0; i<32; i++) {
/*
pixel_topBlock[0][i] = (data_topBlock[2*i + 2] << 8) | data_topBlock[2*i + 3];
pixel_topBlock[1][i] = (data_topBlock[2*(i+32) + 2] << 8) | data_topBlock[2*(i+32) + 3];
pixel_topBlock[2][i] = (data_topBlock[2*(i+64) + 2] << 8) | data_topBlock[2*(i+64) + 3];
pixel_topBlock[3][i] = (data_topBlock[2*(i+96) + 2] << 8) | data_topBlock[2*(i+96) + 3];
*/
pixel_topBlock[i] = (data_topBlock[2*(i+32*HTPA_ROWSELECTION) + 2] << 8) | data_topBlock[2*(i+32*HTPA_ROWSELECTION) + 3];
/*
elOffset[0][i] = (elOffset_topBlock[2*i + 2] << 8) | elOffset_topBlock[2*i + 3];
elOffset[1][i] = (elOffset_topBlock[2*(i+32) + 2] << 8) | elOffset_topBlock[2*(i+32) + 3];
elOffset[2][i] = (elOffset_topBlock[2*(i+64) + 2] << 8) | elOffset_topBlock[2*(i+64) + 3];
elOffset[3][i] = (elOffset_topBlock[2*(i+96) + 2] << 8) | elOffset_topBlock[2*(i+96) + 3];
*/
elOffset[i] = (elOffset_topBlock[2*(i+32*HTPA_ROWSELECTION) + 2] << 8) | elOffset_topBlock[2*(i+32*HTPA_ROWSELECTION) + 3];
}
/*
* calculate temperature
*/
int64_t vij_pixc_and_pcscaleval;
int64_t vdd_calc_steps;
uint16_t table_row, table_col;
int32_t vx, vy, ydist, dta;
// 11.1 ambient temperature:
ambient_temperature = ptat_topBlock * ptatgr + ptatoff; // value in dK
// find column of lookup table (ambient temperature)
for(uint8_t i = 0; i < NROFTAELEMENTS; i++) {
if(ambient_temperature > XTATemps[i]) {
table_col = i;
}
}
dta = ambient_temperature - XTATemps[table_col];
ydist = (int32_t)ADEQUIDISTANCE;
for(int i=0; i<32; i++) {
// 11.2 thermal offset:
vij_comp[i] = pixel_topBlock[i] - (thgrad[i] * ptat_topBlock / gradscale_div) - thoffset[i];
// 11.3 electrical offset:
vij_comp_s[i] = vij_comp[i] - elOffset[i];
// 11.4 Vdd compensation:
vdd_calc_steps = vddcompgrad[i] * ptat_topBlock;
vdd_calc_steps = vdd_calc_steps / vddscgrad_div;
vdd_calc_steps = vdd_calc_steps + vddcompoff[i];
vdd_calc_steps = vdd_calc_steps * (vdd_topBlock - vddth1 - ((vddth2 - vddth1) / (ptatth2 - ptatth1)) * (ptat_topBlock - ptatth1));
vdd_calc_steps = vdd_calc_steps / vddscoff_div;
vij_vddcomp[i] = vij_comp_s[i] - vdd_calc_steps;
// 11.5 calculate object temperature
vij_pixc_and_pcscaleval = (int64_t)vij_vddcomp[i] * (int64_t)PCSCALEVAL;
vij_pixc[i] = (int32_t)(vij_pixc_and_pcscaleval / (int64_t)pixcij[i]);
// find temperature in lookup table and do bilinear interpolation
table_row = vij_pixc[i] + TABLEOFFSET;
table_row = table_row >> ADEXPBITS;
vx = ((((int32_t)TempTable[table_row][table_col + 1] - (int32_t)TempTable[table_row][table_col]) * (int32_t)dta) / (int32_t)TAEQUIDISTANCE) + (int32_t)TempTable[table_row][table_col];
vy = ((((int32_t)TempTable[table_row + 1][table_col + 1] - (int32_t)TempTable[table_row + 1][table_col]) * (int32_t)dta) / (int32_t)TAEQUIDISTANCE) + (int32_t)TempTable[table_row + 1][table_col];
temp_pix[i] = (uint32_t)((vy - vx) * ((int32_t)(vij_pixc[i] + TABLEOFFSET) - (int32_t)YADValues[table_row]) / ydist + (int32_t)vx);
// --- GLOBAL OFFSET ---
temp_pix[i] = temp_pix[i] + globaloff;
dataArray[i] = temp_pix[i] - 2731;
}
}
/**
* @brief Write to selected sensor register
*
* description
*
* @param address: address of register
* @param byte: byte to be written to register
*/
void HTPA_WriteRegister(uint8_t address, uint8_t byte){
HAL_I2C_Mem_Write(htpa_hi2c, (HTPA_SENSOR_ADDRESS << 1), address, I2C_MEMADD_SIZE_8BIT, &byte, 1, HTPA_I2C_MAX_DELAY);
}
/**
* @brief Read from address for specified length
*
* description
*
* @param address: register address
* @param pData: pointer to output data array
* @param length: length of data to be read
*/
void HTPA_ReadRegister(uint8_t address, uint8_t *pData, uint16_t length){
HAL_I2C_Mem_Read(htpa_hi2c, (HTPA_SENSOR_ADDRESS << 1), address, I2C_MEMADD_SIZE_8BIT, pData, length, HTPA_I2C_MAX_DELAY);
}
/**
* @brief Get status of sensor
*
* Reads the sensors status register and stores the information in
* the htpa_statusReg variable
*
*/
void HTPA_GetStatus(void){
uint8_t i2c_readData = 0;
HTPA_ReadRegister(HTPA_SENSOR_STATUS, &i2c_readData, 1);
htpa_statusReg.block = (i2c_readData >> 4) & 0x03;
htpa_statusReg.vdd_meas = (i2c_readData >> 2) & 0x01;
htpa_statusReg.blind = (i2c_readData >> 1) & 0x01;
htpa_statusReg.eoc = i2c_readData & 0x01;
}
/**
* @brief Get status of sensor
*
* Reads the sensors status register and stores the information in
* the htpa_statusReg variable
*
*/
uint8_t HTPA_ReadEEPROM_byte(uint16_t address){
uint8_t data = 0;
HAL_I2C_Mem_Read(htpa_hi2c, (HTPA_EEPROM_ADDRESS << 1), address, I2C_MEMADD_SIZE_16BIT, &data, 1, HTPA_I2C_MAX_DELAY);
return data;
}

329
Software/Core/Src/main.c Normal file
View File

@ -0,0 +1,329 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "HTPA_32x32d.h"
#include "tts.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
CAN_HandleTypeDef hcan;
I2C_HandleTypeDef hi2c1;
/* USER CODE BEGIN PV */
uint32_t pixelTemps[32];
uint32_t tireTemps[5];
uint32_t systicks = 0;
uint8_t blinkCount = 0;
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_CAN_Init(void);
static void MX_I2C1_Init(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
{
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_CAN_Init();
MX_I2C1_Init();
/* USER CODE BEGIN 2 */
HAL_GPIO_WritePin(LED_GPIO_Port, LED_Pin, GPIO_PIN_SET);
HTPA_Init(&hi2c1);
TTS_Init(&hcan);
HAL_GPIO_WritePin(LED_GPIO_Port, LED_Pin, GPIO_PIN_RESET);
HAL_CAN_Start(&hcan);
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
systicks = HAL_GetTick();
if((systicks % 100) <= 1){
if(blinkCount >= 9) {
HAL_GPIO_WritePin(LED_GPIO_Port, LED_Pin, GPIO_PIN_SET);
blinkCount = 0;
}
else {
HAL_GPIO_WritePin(LED_GPIO_Port, LED_Pin, GPIO_PIN_RESET);
blinkCount++;
}
HTPA_ReadSensor(pixelTemps);
TTS_TireZones(pixelTemps,tireTemps);
TTS_SendCAN(tireTemps);
}
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void)
{
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSE;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK)
{
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C1;
PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_SYSCLK;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
}
/**
* @brief CAN Initialization Function
* @param None
* @retval None
*/
static void MX_CAN_Init(void)
{
/* USER CODE BEGIN CAN_Init 0 */
/* USER CODE END CAN_Init 0 */
/* USER CODE BEGIN CAN_Init 1 */
/* USER CODE END CAN_Init 1 */
hcan.Instance = CAN;
hcan.Init.Prescaler = 2;
hcan.Init.Mode = CAN_MODE_NORMAL;
hcan.Init.SyncJumpWidth = CAN_SJW_1TQ;
hcan.Init.TimeSeg1 = CAN_BS1_13TQ;
hcan.Init.TimeSeg2 = CAN_BS2_2TQ;
hcan.Init.TimeTriggeredMode = DISABLE;
hcan.Init.AutoBusOff = DISABLE;
hcan.Init.AutoWakeUp = DISABLE;
hcan.Init.AutoRetransmission = DISABLE;
hcan.Init.ReceiveFifoLocked = DISABLE;
hcan.Init.TransmitFifoPriority = DISABLE;
if (HAL_CAN_Init(&hcan) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN CAN_Init 2 */
/* USER CODE END CAN_Init 2 */
}
/**
* @brief I2C1 Initialization Function
* @param None
* @retval None
*/
static void MX_I2C1_Init(void)
{
/* USER CODE BEGIN I2C1_Init 0 */
/* USER CODE END I2C1_Init 0 */
/* USER CODE BEGIN I2C1_Init 1 */
/* USER CODE END I2C1_Init 1 */
hi2c1.Instance = I2C1;
hi2c1.Init.Timing = 0x0010061A;
hi2c1.Init.OwnAddress1 = 0;
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
hi2c1.Init.OwnAddress2 = 0;
hi2c1.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
if (HAL_I2C_Init(&hi2c1) != HAL_OK)
{
Error_Handler();
}
/** Configure Analogue filter
*/
if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
{
Error_Handler();
}
/** Configure Digital filter
*/
if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN I2C1_Init 2 */
/* USER CODE END I2C1_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
/* USER CODE BEGIN MX_GPIO_Init_1 */
/* USER CODE END MX_GPIO_Init_1 */
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(LED_GPIO_Port, LED_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin : LED_Pin */
GPIO_InitStruct.Pin = LED_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(LED_GPIO_Port, &GPIO_InitStruct);
/* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */
}
/* USER CODE BEGIN 4 */
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void)
{
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
HAL_GPIO_WritePin(LED_GPIO_Port, LED_Pin, GPIO_PIN_SET);
__disable_irq();
while (1)
{
}
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t *file, uint32_t line)
{
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

View File

@ -0,0 +1,217 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f0xx_hal_msp.c
* @brief This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN Define */
/* USER CODE END Define */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN Macro */
/* USER CODE END Macro */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* External functions --------------------------------------------------------*/
/* USER CODE BEGIN ExternalFunctions */
/* USER CODE END ExternalFunctions */
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
{
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */
__HAL_RCC_SYSCFG_CLK_ENABLE();
__HAL_RCC_PWR_CLK_ENABLE();
/* System interrupt init*/
/* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */
}
/**
* @brief CAN MSP Initialization
* This function configures the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hcan->Instance==CAN)
{
/* USER CODE BEGIN CAN_MspInit 0 */
/* USER CODE END CAN_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_CAN1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**CAN GPIO Configuration
PA11 ------> CAN_RX
PA12 ------> CAN_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF4_CAN;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN CAN_MspInit 1 */
/* USER CODE END CAN_MspInit 1 */
}
}
/**
* @brief CAN MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan)
{
if(hcan->Instance==CAN)
{
/* USER CODE BEGIN CAN_MspDeInit 0 */
/* USER CODE END CAN_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_CAN1_CLK_DISABLE();
/**CAN GPIO Configuration
PA11 ------> CAN_RX
PA12 ------> CAN_TX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* USER CODE BEGIN CAN_MspDeInit 1 */
/* USER CODE END CAN_MspDeInit 1 */
}
}
/**
* @brief I2C MSP Initialization
* This function configures the hardware resources used in this example
* @param hi2c: I2C handle pointer
* @retval None
*/
void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hi2c->Instance==I2C1)
{
/* USER CODE BEGIN I2C1_MspInit 0 */
/* USER CODE END I2C1_MspInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
/**I2C1 GPIO Configuration
PB6 ------> I2C1_SCL
PB7 ------> I2C1_SDA
*/
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF1_I2C1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* Peripheral clock enable */
__HAL_RCC_I2C1_CLK_ENABLE();
/* USER CODE BEGIN I2C1_MspInit 1 */
/* USER CODE END I2C1_MspInit 1 */
}
}
/**
* @brief I2C MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hi2c: I2C handle pointer
* @retval None
*/
void HAL_I2C_MspDeInit(I2C_HandleTypeDef* hi2c)
{
if(hi2c->Instance==I2C1)
{
/* USER CODE BEGIN I2C1_MspDeInit 0 */
/* USER CODE END I2C1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_I2C1_CLK_DISABLE();
/**I2C1 GPIO Configuration
PB6 ------> I2C1_SCL
PB7 ------> I2C1_SDA
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_7);
/* USER CODE BEGIN I2C1_MspDeInit 1 */
/* USER CODE END I2C1_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

View File

@ -0,0 +1,145 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f0xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32f0xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/******************************************************************************/
/* Cortex-M0 Processor Interruption and Exception Handlers */
/******************************************************************************/
/**
* @brief This function handles Non maskable interrupt.
*/
void NMI_Handler(void)
{
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
/* USER CODE END NonMaskableInt_IRQn 0 */
/* USER CODE BEGIN NonMaskableInt_IRQn 1 */
while (1)
{
}
/* USER CODE END NonMaskableInt_IRQn 1 */
}
/**
* @brief This function handles Hard fault interrupt.
*/
void HardFault_Handler(void)
{
/* USER CODE BEGIN HardFault_IRQn 0 */
/* USER CODE END HardFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_HardFault_IRQn 0 */
/* USER CODE END W1_HardFault_IRQn 0 */
}
}
/**
* @brief This function handles System service call via SWI instruction.
*/
void SVC_Handler(void)
{
/* USER CODE BEGIN SVC_IRQn 0 */
/* USER CODE END SVC_IRQn 0 */
/* USER CODE BEGIN SVC_IRQn 1 */
/* USER CODE END SVC_IRQn 1 */
}
/**
* @brief This function handles Pendable request for system service.
*/
void PendSV_Handler(void)
{
/* USER CODE BEGIN PendSV_IRQn 0 */
/* USER CODE END PendSV_IRQn 0 */
/* USER CODE BEGIN PendSV_IRQn 1 */
/* USER CODE END PendSV_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();
/* USER CODE BEGIN SysTick_IRQn 1 */
/* USER CODE END SysTick_IRQn 1 */
}
/******************************************************************************/
/* STM32F0xx Peripheral Interrupt Handlers */
/* Add here the Interrupt Handlers for the used peripherals. */
/* For the available peripheral interrupt handler names, */
/* please refer to the startup file (startup_stm32f0xx.s). */
/******************************************************************************/
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

View File

@ -0,0 +1,176 @@
/**
******************************************************************************
* @file syscalls.c
* @author Auto-generated by STM32CubeIDE
* @brief STM32CubeIDE Minimal System calls file
*
* For more information about which c-functions
* need which of these lowlevel functions
* please consult the Newlib libc-manual
******************************************************************************
* @attention
*
* Copyright (c) 2020-2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* Includes */
#include <sys/stat.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <signal.h>
#include <time.h>
#include <sys/time.h>
#include <sys/times.h>
/* Variables */
extern int __io_putchar(int ch) __attribute__((weak));
extern int __io_getchar(void) __attribute__((weak));
char *__env[1] = { 0 };
char **environ = __env;
/* Functions */
void initialise_monitor_handles()
{
}
int _getpid(void)
{
return 1;
}
int _kill(int pid, int sig)
{
(void)pid;
(void)sig;
errno = EINVAL;
return -1;
}
void _exit (int status)
{
_kill(status, -1);
while (1) {} /* Make sure we hang here */
}
__attribute__((weak)) int _read(int file, char *ptr, int len)
{
(void)file;
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
*ptr++ = __io_getchar();
}
return len;
}
__attribute__((weak)) int _write(int file, char *ptr, int len)
{
(void)file;
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
__io_putchar(*ptr++);
}
return len;
}
int _close(int file)
{
(void)file;
return -1;
}
int _fstat(int file, struct stat *st)
{
(void)file;
st->st_mode = S_IFCHR;
return 0;
}
int _isatty(int file)
{
(void)file;
return 1;
}
int _lseek(int file, int ptr, int dir)
{
(void)file;
(void)ptr;
(void)dir;
return 0;
}
int _open(char *path, int flags, ...)
{
(void)path;
(void)flags;
/* Pretend like we always fail */
return -1;
}
int _wait(int *status)
{
(void)status;
errno = ECHILD;
return -1;
}
int _unlink(char *name)
{
(void)name;
errno = ENOENT;
return -1;
}
int _times(struct tms *buf)
{
(void)buf;
return -1;
}
int _stat(char *file, struct stat *st)
{
(void)file;
st->st_mode = S_IFCHR;
return 0;
}
int _link(char *old, char *new)
{
(void)old;
(void)new;
errno = EMLINK;
return -1;
}
int _fork(void)
{
errno = EAGAIN;
return -1;
}
int _execve(char *name, char **argv, char **env)
{
(void)name;
(void)argv;
(void)env;
errno = ENOMEM;
return -1;
}

View File

@ -0,0 +1,79 @@
/**
******************************************************************************
* @file sysmem.c
* @author Generated by STM32CubeIDE
* @brief STM32CubeIDE System Memory calls file
*
* For more information about which C functions
* need which of these lowlevel functions
* please consult the newlib libc manual
******************************************************************************
* @attention
*
* Copyright (c) 2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* Includes */
#include <errno.h>
#include <stdint.h>
/**
* Pointer to the current high watermark of the heap usage
*/
static uint8_t *__sbrk_heap_end = NULL;
/**
* @brief _sbrk() allocates memory to the newlib heap and is used by malloc
* and others from the C library
*
* @verbatim
* ############################################################################
* # .data # .bss # newlib heap # MSP stack #
* # # # # Reserved by _Min_Stack_Size #
* ############################################################################
* ^-- RAM start ^-- _end _estack, RAM end --^
* @endverbatim
*
* This implementation starts allocating at the '_end' linker symbol
* The '_Min_Stack_Size' linker symbol reserves a memory for the MSP stack
* The implementation considers '_estack' linker symbol to be RAM end
* NOTE: If the MSP stack, at any point during execution, grows larger than the
* reserved size, please increase the '_Min_Stack_Size'.
*
* @param incr Memory size
* @return Pointer to allocated memory
*/
void *_sbrk(ptrdiff_t incr)
{
extern uint8_t _end; /* Symbol defined in the linker script */
extern uint8_t _estack; /* Symbol defined in the linker script */
extern uint32_t _Min_Stack_Size; /* Symbol defined in the linker script */
const uint32_t stack_limit = (uint32_t)&_estack - (uint32_t)&_Min_Stack_Size;
const uint8_t *max_heap = (uint8_t *)stack_limit;
uint8_t *prev_heap_end;
/* Initialize heap end at first call */
if (NULL == __sbrk_heap_end)
{
__sbrk_heap_end = &_end;
}
/* Protect heap from growing into the reserved MSP stack */
if (__sbrk_heap_end + incr > max_heap)
{
errno = ENOMEM;
return (void *)-1;
}
prev_heap_end = __sbrk_heap_end;
__sbrk_heap_end += incr;
return (void *)prev_heap_end;
}

View File

@ -0,0 +1,249 @@
/**
******************************************************************************
* @file system_stm32f0xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File.
*
* 1. This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32f0xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
*
******************************************************************************
* @attention
*
* Copyright (c) 2016 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f0xx_system
* @{
*/
/** @addtogroup STM32F0xx_System_Private_Includes
* @{
*/
#include "stm32f0xx.h"
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Defines
* @{
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSE_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSI_VALUE */
#if !defined (HSI48_VALUE)
#define HSI48_VALUE ((uint32_t)48000000) /*!< Default value of the HSI48 Internal oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSI48_VALUE */
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Variables
* @{
*/
/* This variable is updated in three ways:
1) by calling CMSIS function SystemCoreClockUpdate()
2) by calling HAL API function HAL_RCC_GetHCLKFreq()
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
Note: If you use this function to configure the system clock; then there
is no need to call the 2 first functions listed above, since SystemCoreClock
variable is updated automatically.
*/
uint32_t SystemCoreClock = 8000000;
const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system
* @param None
* @retval None
*/
void SystemInit(void)
{
/* NOTE :SystemInit(): This function is called at startup just after reset and
before branch to main program. This call is made inside
the "startup_stm32f0xx.s" file.
User can setups the default system clock (System clock source, PLL Multiplier
and Divider factors, AHB/APBx prescalers and Flash settings).
*/
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
*
* - If SYSCLK source is HSI48, SystemCoreClock will contain the HSI48_VALUE(***)
*
* (*) HSI_VALUE is a constant defined in stm32f0xx_hal_conf.h file (default value
* 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f0xx_hal_conf.h file (its value
* depends on the application requirements), user has to ensure that HSE_VALUE
* is same as the real frequency of the crystal used. Otherwise, this function
* may have wrong result.
*
* (***) HSI48_VALUE is a constant defined in stm32f0xx_hal_conf.h file (default value
* 48 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @param None
* @retval None
*/
void SystemCoreClockUpdate (void)
{
uint32_t tmp = 0, pllmull = 0, pllsource = 0, predivfactor = 0;
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
case RCC_CFGR_SWS_HSI: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
case RCC_CFGR_SWS_HSE: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
break;
case RCC_CFGR_SWS_PLL: /* PLL used as system clock */
/* Get PLL clock source and multiplication factor ----------------------*/
pllmull = RCC->CFGR & RCC_CFGR_PLLMUL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = ( pllmull >> 18) + 2;
predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1;
if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV)
{
/* HSE used as PLL clock source : SystemCoreClock = HSE/PREDIV * PLLMUL */
SystemCoreClock = (HSE_VALUE/predivfactor) * pllmull;
}
#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F091xC) || defined(STM32F098xx)
else if (pllsource == RCC_CFGR_PLLSRC_HSI48_PREDIV)
{
/* HSI48 used as PLL clock source : SystemCoreClock = HSI48/PREDIV * PLLMUL */
SystemCoreClock = (HSI48_VALUE/predivfactor) * pllmull;
}
#endif /* STM32F042x6 || STM32F048xx || STM32F071xB || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx */
else
{
#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6) \
|| defined(STM32F078xx) || defined(STM32F071xB) || defined(STM32F072xB) \
|| defined(STM32F070xB) || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
/* HSI used as PLL clock source : SystemCoreClock = HSI/PREDIV * PLLMUL */
SystemCoreClock = (HSI_VALUE/predivfactor) * pllmull;
#else
/* HSI used as PLL clock source : SystemCoreClock = HSI/2 * PLLMUL */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 ||
STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB ||
STM32F091xC || STM32F098xx || STM32F030xC */
}
break;
default: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
}
/* Compute HCLK clock frequency ----------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

184
Software/Core/Src/tts.c Normal file
View File

@ -0,0 +1,184 @@
/*
* tts.c
*
* Created on: Jun 28, 2024
* Author: ted
*/
#include "tts.h"
#include "HTPA_32x32d.h"
// CAN Frame:
#define TTS_CANIDSTART 0x701; //
CAN_HandleTypeDef* tts_hcan;
CAN_TxHeaderTypeDef tts_canHeader;
uint8_t tts_canData[8];
uint32_t tts_canMailbox;
// Car / Tire info:
TTS_SensorID tts_sensorid;
TTS_CarID tts_carid;
TTS_TireID tts_tireid;
TTS_TireData tts_tiredb[4];
void TTS_Init(CAN_HandleTypeDef *hcan) {
// initialize values
TTS_LoadTireData();
tts_sensorid = TTS_FL;
tts_carid = FT24;
tts_tireid = OZ7_SLICKS;
// init CAN
tts_hcan = hcan;
// set CAN filter
/*
CAN_FilterTypeDef canfilterconfig;
canfilterconfig.FilterActivation = CAN_FILTER_ENABLE;
canfilterconfig.FilterBank = 0;
canfilterconfig.FilterFIFOAssignment = CAN_FILTER_FIFO0;
canfilterconfig.FilterIdHigh = 0x704<<5;
canfilterconfig.FilterIdLow = 0x700<<5;
canfilterconfig.FilterMaskIdHigh = 0x704<<5;
canfilterconfig.FilterMaskIdLow = 0x700<<5;
canfilterconfig.FilterMode = CAN_FILTERMODE_IDMASK;
canfilterconfig.FilterScale = CAN_FILTERSCALE_32BIT;
HAL_CAN_ConfigFilter(tts_hcan, &canfilterconfig);
*/
// init CAN_Tx Frame
//uint8_t canID = tts_sensorid + TTS_CANIDSTART;
tts_canHeader.IDE = CAN_ID_STD;
tts_canHeader.StdId = 0x701;
tts_canHeader.DLC = 8;
tts_canHeader.RTR = CAN_RTR_DATA;
for(uint8_t i=0; i<8; i++) {
tts_canData[i] = 0xFF;
}
}
void TTS_SendCAN(uint32_t tireZones[5]) {
// Outer left:
tts_canData[0] = tireZones[0] & 0xFF;
tts_canData[1] = (tireZones[0] >> 8) & 0xF;
// Center left:
tts_canData[1] = tts_canData[1] | ((tireZones[1] & 0xF) << 4);
tts_canData[2] = (tireZones[1] >> 4) & 0xFF;
// Center:
tts_canData[3] = tireZones[2] & 0xFF;
tts_canData[4] = (tireZones[2] >> 8) & 0xF;
// Center right:
tts_canData[4] = tts_canData[4] | ((tireZones[3] & 0xF) << 4);
tts_canData[5] = (tireZones[3] >> 4) & 0xFF;
// Center right:
tts_canData[6] = tireZones[4] & 0xFF;
tts_canData[7] = (tireZones[4] >> 8) & 0xF;
// current tire selected:
//tts_canData[7] = tts_canData[7] | ((tts_tireid & 0xF) << 4);
if(HAL_CAN_AddTxMessage(tts_hcan, &tts_canHeader, tts_canData, &tts_canMailbox) != HAL_OK) {
Error_Handler();
}
}
void TTS_TireZones(uint32_t tempArray[32], uint32_t tireTempArray[5]) {
for(uint8_t i = 0; i < 5; i++) {
tireTempArray[i] = 0;
}
uint8_t zoneWidth[5] = {0};
uint8_t tireid = tts_tireid;
for(uint8_t i = 0; i < 32; i++) {
// outer right:
if((i <= tts_tiredb[tts_tireid].outerRightStart) && (i >= tts_tiredb[tts_tireid].outerRightStop)) {
tireTempArray[4] = tireTempArray[4] + tempArray[i];
zoneWidth[4]++;
}
// center right:
if((i <= tts_tiredb[tts_tireid].centerRightStart) && (i >= tts_tiredb[tts_tireid].centerRightStop)) {
tireTempArray[3] = tireTempArray[3] + tempArray[i];
zoneWidth[3]++;
}
// center:
if((i <= tts_tiredb[tts_tireid].centerStart) && (i >= tts_tiredb[tts_tireid].centerStop)) {
tireTempArray[2] = tireTempArray[2] + tempArray[i];
zoneWidth[2]++;
}
// center left:
if((i <= tts_tiredb[tts_tireid].centerLeftStart) && (i >= tts_tiredb[tts_tireid].centerLeftStop)) {
tireTempArray[1] = tireTempArray[1] + tempArray[i];
zoneWidth[1]++;
}
// outer left:
if((i <= tts_tiredb[tts_tireid].outerLeftStart) && (i >= tts_tiredb[tts_tireid].outerLeftStop)) {
tireTempArray[0] = tireTempArray[0] + tempArray[i];
zoneWidth[0]++;
}
}
tireTempArray[4] = tireTempArray[4] / zoneWidth[4];
tireTempArray[3] = tireTempArray[3] / zoneWidth[3];
tireTempArray[2] = tireTempArray[2] / zoneWidth[2];
tireTempArray[1] = tireTempArray[1] / zoneWidth[1];
tireTempArray[0] = tireTempArray[0] / zoneWidth[0];
}
void TTS_LoadTireData(void) {
tts_tiredb[UNKNOWN].id = UNKNOWN;
tts_tiredb[UNKNOWN].epsilon = 84;
tts_tiredb[UNKNOWN].outerLeftStart = 31;
tts_tiredb[UNKNOWN].outerLeftStop = 26;
tts_tiredb[UNKNOWN].centerLeftStart = 25;
tts_tiredb[UNKNOWN].centerLeftStop = 20;
tts_tiredb[UNKNOWN].centerStart = 19;
tts_tiredb[UNKNOWN].centerStop = 12;
tts_tiredb[UNKNOWN].centerRightStart = 11;
tts_tiredb[UNKNOWN].centerRightStop = 6;
tts_tiredb[UNKNOWN].outerRightStart = 5;
tts_tiredb[UNKNOWN].outerRightStop = 0;
tts_tiredb[OZ7_SLICKS].id = OZ7_SLICKS;
tts_tiredb[OZ7_SLICKS].epsilon = 84;
tts_tiredb[OZ7_SLICKS].outerLeftStart = 27;
tts_tiredb[OZ7_SLICKS].outerLeftStop = 25;
tts_tiredb[OZ7_SLICKS].centerLeftStart = 24;
tts_tiredb[OZ7_SLICKS].centerLeftStop = 19;
tts_tiredb[OZ7_SLICKS].centerStart = 18;
tts_tiredb[OZ7_SLICKS].centerStop = 13;
tts_tiredb[OZ7_SLICKS].centerRightStart = 12;
tts_tiredb[OZ7_SLICKS].centerRightStop = 7;
tts_tiredb[OZ7_SLICKS].outerRightStart = 6;
tts_tiredb[OZ7_SLICKS].outerRightStop = 4;
tts_tiredb[OZ7_RAIN].id = OZ7_RAIN;
tts_tiredb[OZ7_RAIN].epsilon = 84;
tts_tiredb[OZ7_RAIN].outerLeftStart = 31;
tts_tiredb[OZ7_RAIN].outerLeftStop = 26;
tts_tiredb[OZ7_RAIN].centerLeftStart = 25;
tts_tiredb[OZ7_RAIN].centerLeftStop = 20;
tts_tiredb[OZ7_RAIN].centerStart = 19;
tts_tiredb[OZ7_RAIN].centerStop = 12;
tts_tiredb[OZ7_RAIN].centerRightStart = 11;
tts_tiredb[OZ7_RAIN].centerRightStop = 6;
tts_tiredb[OZ7_RAIN].outerRightStart = 5;
tts_tiredb[OZ7_RAIN].outerRightStop = 0;
tts_tiredb[JP8_SLICKS].id = JP8_SLICKS;
tts_tiredb[JP8_SLICKS].epsilon = 84;
tts_tiredb[JP8_SLICKS].outerLeftStart = 28;
tts_tiredb[JP8_SLICKS].outerLeftStop = 24;
tts_tiredb[JP8_SLICKS].centerLeftStart = 23;
tts_tiredb[JP8_SLICKS].centerLeftStop = 19;
tts_tiredb[JP8_SLICKS].centerStart = 18;
tts_tiredb[JP8_SLICKS].centerStop = 13;
tts_tiredb[JP8_SLICKS].centerRightStart = 12;
tts_tiredb[JP8_SLICKS].centerRightStop = 8;
tts_tiredb[JP8_SLICKS].outerRightStart = 7;
tts_tiredb[JP8_SLICKS].outerRightStop = 3;
}

View File

@ -0,0 +1,309 @@
/**
******************************************************************************
* @file startup_stm32f042x6.s
* @author MCD Application Team
* @brief STM32F042x4/STM32F042x6 devices vector table for GCC 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.
******************************************************************************
* @attention
*
* Copyright (c) 2016 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
.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
/**
* @brief This is the code that gets called when the processor first
* starts execution following a reset event. Only the absolutely
* necessary set is performed, after which the application
* supplied main() routine is called.
* @param None
* @retval : None
*/
.section .text.Reset_Handler
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
ldr r0, =_estack
mov sp, r0 /* set stack pointer */
/* Call the clock system initialization function.*/
bl SystemInit
/*Check if boot space corresponds to test memory*/
LDR R0,=0x00000004
LDR R1, [R0]
LSRS R1, R1, #24
LDR R2,=0x1F
CMP R1, R2
BNE ApplicationStart
/*SYSCFG clock enable*/
LDR R0,=0x40021018
LDR R1,=0x00000001
STR R1, [R0]
/*Set CFGR1 register with flash memory remap at address 0*/
LDR R0,=0x40010000
LDR R1,=0x00000000
STR R1, [R0]
ApplicationStart:
/* Copy the data segment initializers from flash to SRAM */
ldr r0, =_sdata
ldr r1, =_edata
ldr r2, =_sidata
movs r3, #0
b LoopCopyDataInit
CopyDataInit:
ldr r4, [r2, r3]
str r4, [r0, r3]
adds r3, r3, #4
LoopCopyDataInit:
adds r4, r0, r3
cmp r4, r1
bcc CopyDataInit
/* Zero fill the bss segment. */
ldr r2, =_sbss
ldr r4, =_ebss
movs r3, #0
b LoopFillZerobss
FillZerobss:
str r3, [r2]
adds r2, r2, #4
LoopFillZerobss:
cmp r2, r4
bcc FillZerobss
/* 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 */
.word TIM2_IRQHandler /* TIM2 */
.word TIM3_IRQHandler /* TIM3 */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word TIM14_IRQHandler /* TIM14 */
.word 0 /* Reserved */
.word TIM16_IRQHandler /* TIM16 */
.word TIM17_IRQHandler /* TIM17 */
.word I2C1_IRQHandler /* I2C1 */
.word 0 /* Reserved */
.word SPI1_IRQHandler /* SPI1 */
.word SPI2_IRQHandler /* SPI2 */
.word USART1_IRQHandler /* USART1 */
.word USART2_IRQHandler /* USART2 */
.word 0 /* Reserved */
.word CEC_CAN_IRQHandler /* CEC and CAN */
.word USB_IRQHandler /* USB */
/*******************************************************************************
*
* Provide weak aliases for each Exception handler to the Default_Handler.
* As they are weak aliases, any function with the same name will override
* this definition.
*
*******************************************************************************/
.weak NMI_Handler
.thumb_set NMI_Handler,Default_Handler
.weak HardFault_Handler
.thumb_set HardFault_Handler,Default_Handler
.weak SVC_Handler
.thumb_set SVC_Handler,Default_Handler
.weak PendSV_Handler
.thumb_set PendSV_Handler,Default_Handler
.weak SysTick_Handler
.thumb_set SysTick_Handler,Default_Handler
.weak WWDG_IRQHandler
.thumb_set WWDG_IRQHandler,Default_Handler
.weak PVD_VDDIO2_IRQHandler
.thumb_set PVD_VDDIO2_IRQHandler,Default_Handler
.weak RTC_IRQHandler
.thumb_set RTC_IRQHandler,Default_Handler
.weak FLASH_IRQHandler
.thumb_set FLASH_IRQHandler,Default_Handler
.weak RCC_CRS_IRQHandler
.thumb_set RCC_CRS_IRQHandler,Default_Handler
.weak EXTI0_1_IRQHandler
.thumb_set EXTI0_1_IRQHandler,Default_Handler
.weak EXTI2_3_IRQHandler
.thumb_set EXTI2_3_IRQHandler,Default_Handler
.weak EXTI4_15_IRQHandler
.thumb_set EXTI4_15_IRQHandler,Default_Handler
.weak TSC_IRQHandler
.thumb_set TSC_IRQHandler,Default_Handler
.weak DMA1_Channel1_IRQHandler
.thumb_set DMA1_Channel1_IRQHandler,Default_Handler
.weak DMA1_Channel2_3_IRQHandler
.thumb_set DMA1_Channel2_3_IRQHandler,Default_Handler
.weak DMA1_Channel4_5_IRQHandler
.thumb_set DMA1_Channel4_5_IRQHandler,Default_Handler
.weak ADC1_IRQHandler
.thumb_set ADC1_IRQHandler,Default_Handler
.weak TIM1_BRK_UP_TRG_COM_IRQHandler
.thumb_set TIM1_BRK_UP_TRG_COM_IRQHandler,Default_Handler
.weak TIM1_CC_IRQHandler
.thumb_set TIM1_CC_IRQHandler,Default_Handler
.weak TIM2_IRQHandler
.thumb_set TIM2_IRQHandler,Default_Handler
.weak TIM3_IRQHandler
.thumb_set TIM3_IRQHandler,Default_Handler
.weak TIM14_IRQHandler
.thumb_set TIM14_IRQHandler,Default_Handler
.weak TIM16_IRQHandler
.thumb_set TIM16_IRQHandler,Default_Handler
.weak TIM17_IRQHandler
.thumb_set TIM17_IRQHandler,Default_Handler
.weak I2C1_IRQHandler
.thumb_set I2C1_IRQHandler,Default_Handler
.weak SPI1_IRQHandler
.thumb_set SPI1_IRQHandler,Default_Handler
.weak SPI2_IRQHandler
.thumb_set SPI2_IRQHandler,Default_Handler
.weak USART1_IRQHandler
.thumb_set USART1_IRQHandler,Default_Handler
.weak USART2_IRQHandler
.thumb_set USART2_IRQHandler,Default_Handler
.weak CEC_CAN_IRQHandler
.thumb_set CEC_CAN_IRQHandler,Default_Handler
.weak USB_IRQHandler
.thumb_set USB_IRQHandler,Default_Handler

View File

@ -0,0 +1,309 @@
/**
******************************************************************************
* @file startup_stm32f042x6.s
* @author MCD Application Team
* @brief STM32F042x4/STM32F042x6 devices vector table for GCC 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.
******************************************************************************
* @attention
*
* Copyright (c) 2016 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
.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
/**
* @brief This is the code that gets called when the processor first
* starts execution following a reset event. Only the absolutely
* necessary set is performed, after which the application
* supplied main() routine is called.
* @param None
* @retval : None
*/
.section .text.Reset_Handler
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
ldr r0, =_estack
mov sp, r0 /* set stack pointer */
/* Call the clock system initialization function.*/
bl SystemInit
/*Check if boot space corresponds to test memory*/
LDR R0,=0x00000004
LDR R1, [R0]
LSRS R1, R1, #24
LDR R2,=0x1F
CMP R1, R2
BNE ApplicationStart
/*SYSCFG clock enable*/
LDR R0,=0x40021018
LDR R1,=0x00000001
STR R1, [R0]
/*Set CFGR1 register with flash memory remap at address 0*/
LDR R0,=0x40010000
LDR R1,=0x00000000
STR R1, [R0]
ApplicationStart:
/* Copy the data segment initializers from flash to SRAM */
ldr r0, =_sdata
ldr r1, =_edata
ldr r2, =_sidata
movs r3, #0
b LoopCopyDataInit
CopyDataInit:
ldr r4, [r2, r3]
str r4, [r0, r3]
adds r3, r3, #4
LoopCopyDataInit:
adds r4, r0, r3
cmp r4, r1
bcc CopyDataInit
/* Zero fill the bss segment. */
ldr r2, =_sbss
ldr r4, =_ebss
movs r3, #0
b LoopFillZerobss
FillZerobss:
str r3, [r2]
adds r2, r2, #4
LoopFillZerobss:
cmp r2, r4
bcc FillZerobss
/* 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 */
.word TIM2_IRQHandler /* TIM2 */
.word TIM3_IRQHandler /* TIM3 */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word TIM14_IRQHandler /* TIM14 */
.word 0 /* Reserved */
.word TIM16_IRQHandler /* TIM16 */
.word TIM17_IRQHandler /* TIM17 */
.word I2C1_IRQHandler /* I2C1 */
.word 0 /* Reserved */
.word SPI1_IRQHandler /* SPI1 */
.word SPI2_IRQHandler /* SPI2 */
.word USART1_IRQHandler /* USART1 */
.word USART2_IRQHandler /* USART2 */
.word 0 /* Reserved */
.word CEC_CAN_IRQHandler /* CEC and CAN */
.word USB_IRQHandler /* USB */
/*******************************************************************************
*
* Provide weak aliases for each Exception handler to the Default_Handler.
* As they are weak aliases, any function with the same name will override
* this definition.
*
*******************************************************************************/
.weak NMI_Handler
.thumb_set NMI_Handler,Default_Handler
.weak HardFault_Handler
.thumb_set HardFault_Handler,Default_Handler
.weak SVC_Handler
.thumb_set SVC_Handler,Default_Handler
.weak PendSV_Handler
.thumb_set PendSV_Handler,Default_Handler
.weak SysTick_Handler
.thumb_set SysTick_Handler,Default_Handler
.weak WWDG_IRQHandler
.thumb_set WWDG_IRQHandler,Default_Handler
.weak PVD_VDDIO2_IRQHandler
.thumb_set PVD_VDDIO2_IRQHandler,Default_Handler
.weak RTC_IRQHandler
.thumb_set RTC_IRQHandler,Default_Handler
.weak FLASH_IRQHandler
.thumb_set FLASH_IRQHandler,Default_Handler
.weak RCC_CRS_IRQHandler
.thumb_set RCC_CRS_IRQHandler,Default_Handler
.weak EXTI0_1_IRQHandler
.thumb_set EXTI0_1_IRQHandler,Default_Handler
.weak EXTI2_3_IRQHandler
.thumb_set EXTI2_3_IRQHandler,Default_Handler
.weak EXTI4_15_IRQHandler
.thumb_set EXTI4_15_IRQHandler,Default_Handler
.weak TSC_IRQHandler
.thumb_set TSC_IRQHandler,Default_Handler
.weak DMA1_Channel1_IRQHandler
.thumb_set DMA1_Channel1_IRQHandler,Default_Handler
.weak DMA1_Channel2_3_IRQHandler
.thumb_set DMA1_Channel2_3_IRQHandler,Default_Handler
.weak DMA1_Channel4_5_IRQHandler
.thumb_set DMA1_Channel4_5_IRQHandler,Default_Handler
.weak ADC1_IRQHandler
.thumb_set ADC1_IRQHandler,Default_Handler
.weak TIM1_BRK_UP_TRG_COM_IRQHandler
.thumb_set TIM1_BRK_UP_TRG_COM_IRQHandler,Default_Handler
.weak TIM1_CC_IRQHandler
.thumb_set TIM1_CC_IRQHandler,Default_Handler
.weak TIM2_IRQHandler
.thumb_set TIM2_IRQHandler,Default_Handler
.weak TIM3_IRQHandler
.thumb_set TIM3_IRQHandler,Default_Handler
.weak TIM14_IRQHandler
.thumb_set TIM14_IRQHandler,Default_Handler
.weak TIM16_IRQHandler
.thumb_set TIM16_IRQHandler,Default_Handler
.weak TIM17_IRQHandler
.thumb_set TIM17_IRQHandler,Default_Handler
.weak I2C1_IRQHandler
.thumb_set I2C1_IRQHandler,Default_Handler
.weak SPI1_IRQHandler
.thumb_set SPI1_IRQHandler,Default_Handler
.weak SPI2_IRQHandler
.thumb_set SPI2_IRQHandler,Default_Handler
.weak USART1_IRQHandler
.thumb_set USART1_IRQHandler,Default_Handler
.weak USART2_IRQHandler
.thumb_set USART2_IRQHandler,Default_Handler
.weak CEC_CAN_IRQHandler
.thumb_set CEC_CAN_IRQHandler,Default_Handler
.weak USB_IRQHandler
.thumb_set USB_IRQHandler,Default_Handler