Initial commit

This commit is contained in:
jazzpi
2022-07-03 17:24:42 +02:00
commit b49ac54166
112 changed files with 130091 additions and 0 deletions

View File

@ -0,0 +1,59 @@
/*
* AIR_State_Maschine.h
*
* Created on: Jun 15, 2022
* Author: max
*/
#ifndef INC_AIR_STATE_MASCHINE_H_
#define INC_AIR_STATE_MASCHINE_H_
#include "main.h"
#include "stm32g441xx.h"
#include "stm32g4xx_hal.h"
#define TS_INACTIVE 0
#define TS_PRECHARGE 2
#define TS_DISCHARGE 3
#define TS_ERROR 4
#define TS_ACTIVE 1
#define ADC_READ_TIMEOUT 500 // in ms
#define SDC_LOWER_THRESHOLD 2500 // in ADC Values
// FIXME
#define LOWER_VEHICLE_SIDE_VOLTAGE_LIMIT 150000 // in mV
typedef struct {
int32_t BatteryVoltageVehicleSide;
int32_t BatteryVoltageBatterySide;
uint8_t targetTSState;
uint8_t currentTSState;
uint16_t AIRPrechargeCurrent; // ADC Value
uint16_t AIRPositiveCurrent; // ADC Value
uint16_t AIRNegativeCurrent; // ADC Value
uint16_t RelaisSupplyVoltage;
uint16_t ShutdownCircuitVoltage;
} AIRStateHandler;
AIRStateHandler init_AIR_State_Maschine(ADC_HandleTypeDef* relay_adc,
ADC_HandleTypeDef* sc_adc,
DMA_HandleTypeDef* relay_dma,
DMA_HandleTypeDef* sc_dma);
void Update_AIR_Info(AIRStateHandler* airstate);
uint8_t Update_AIR_State(AIRStateHandler* airstate);
void Activate_TS(AIRStateHandler* airstate);
void Deactivate_TS(AIRStateHandler* airstate);
void AIR_Precharge_Position();
void AIR_Inactive_Position();
void AIR_Discharge_Position();
void AIR_Active_Position();
void AIR_Error_Position();
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc);
#endif /* INC_AIR_STATE_MASCHINE_H_ */

16
Core/Inc/AMS_Errorcodes.h Normal file
View File

@ -0,0 +1,16 @@
/*
* AMS_Errorcodes.h
*
* Created on: Jun 16, 2022
* Author: max
*/
#ifndef INC_AMS_ERRORCODES_H_
#define INC_AMS_ERRORCODES_H_
#include "main.h"
#define SlavesTimeoutError 1
#define SlavesErrorFrameError 2
#endif /* INC_AMS_ERRORCODES_H_ */

View File

@ -0,0 +1,45 @@
/*
* CAN_Communication.h
*
* Created on: Apr 26, 2022
* Author: max
*/
#ifndef INC_CAN_COMMUNICATION_H_
#define INC_CAN_COMMUNICATION_H_
#include "AMS_Errorcodes.h"
#include "Slave_Monitoring.h"
#include "main.h"
#include "stm32g4xx_hal.h"
#include "stm32g4xx_hal_fdcan.h"
#define CANFRAMEBUFFERSIZE 256
// Frame ID = Base Address + Slave ID + MessageNr.
#define SLAVE_STATUS_BASE_ADDRESS 0x600
#define SLAVE_CMD_BASE_ADDRESS 0x500 //
#define SLAVE_EMERGENCY_ADDRESS 0x001 // Emergency Frame
typedef struct {
int16_t FrameID;
uint8_t data[8];
uint8_t length;
uint32_t timestamp;
uint8_t error;
} canFrame;
extern canFrame framebuffer[CANFRAMEBUFFERSIZE];
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef* handle,
uint32_t interrupt_flags);
void CAN_Init(FDCAN_HandleTypeDef* hcan);
uint8_t CAN_Receive(FDCAN_HandleTypeDef* hcan);
uint8_t CAN_Transmit(FDCAN_HandleTypeDef* hcan, uint16_t frameid,
uint8_t* buffer, uint8_t datalen);
void updateSlaveInfo(uint8_t slaveID, uint8_t MessageID, canFrame rxFrame);
#endif /* INC_CAN_COMMUNICATION_H_ */

30
Core/Inc/Error_Check.h Normal file
View File

@ -0,0 +1,30 @@
/*
* Error_Check.h
*
* Created on: Jun 16, 2022
* Author: max
*/
#ifndef INC_ERROR_CHECK_H_
#define INC_ERROR_CHECK_H_
#include "main.h"
typedef struct {
uint8_t IMD_ERROR;
uint8_t AMS_ERROR_LED;
uint8_t IMD_ERROR_LED;
uint8_t TS_no_voltage_error;
uint8_t positive_AIR_or_PC_error;
uint8_t negative_AIR_error;
uint8_t HV_inactive;
uint8_t negative_AIR_open;
uint8_t positive_AIR_and_PC_open;
} ErrorFlags;
ErrorFlags CheckErrorFlags();
#endif /* INC_ERROR_CHECK_H_ */

View File

@ -0,0 +1,45 @@
/*
* SPI_Slave_Communication.h
*
* Created on: Jun 16, 2022
* Author: max
*/
#ifndef SPI_SLAVE_COMMUNICATION_H_
#define SPI_SLAVE_COMMUNICATION_H_
#include "AIR_State_Maschine.h"
#include "Slave_Monitoring.h"
#include "main.h"
#include "stm32g4xx_hal_crc.h"
#define SET_SHUNTDATA 0x01
#define SET_TSSTATE 0x02
#define GET_TSSTATE 0x03
#define GET_ERROR 0x04
#define GET_MEASUREMENTS 0x05
#define TOGGLE_STATUS_LED 0x06
#define SET_SHUNTDATA_CMD_LEN 14
#define SET_TSSTATE_CMD_LEN 2
#define GET_TSSTATE_CMD_LEN 1
#define GET_ERROR_CMD_LEN 1
#define GET_MEASUREMENTS_CMD_LEN 1
void spi_communication_init(SPI_HandleTypeDef* spi,
AIRStateHandler* airstatemaschine);
void checkSPI();
void set_SPI_errorInfo(AMSErrorHandle* errorinfo);
uint8_t checkXor(uint8_t* buf, uint8_t len);
uint8_t calculateChecksum(uint8_t* buf, uint8_t len);
uint8_t receiveData(uint16_t length);
uint8_t transmitData(uint16_t length);
void InterSTMFrame();
void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef* hspi);
void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef* hspi);
void HAL_SPI_ErrorCallback(SPI_HandleTypeDef* hspi);
#endif /* SPI_SLAVE_COMMUNICATION_H_ */

View File

@ -0,0 +1,40 @@
/*
* Slave_Monitoring.h
*
* Created on: Jun 15, 2022
* Author: max
*/
#ifndef INC_SLAVE_MONITORING_H_
#define INC_SLAVE_MONITORING_H_
#include "AMS_Errorcodes.h"
#include "Error_Check.h"
#include "main.h"
#include "stm32g441xx.h"
#define NUMBEROFSLAVES 6
#define NUMBEROFCELLS 10
#define NUMBEROFTEMPS 32
#define SLAVETIMEOUT 2000
typedef struct {
uint16_t slaveID;
uint16_t cellVoltages[NUMBEROFCELLS];
uint16_t cellTemps[NUMBEROFTEMPS];
uint32_t timestamp;
uint8_t error;
uint8_t timeout;
} SlaveHandler;
extern SlaveHandler slaves[NUMBEROFSLAVES];
void initSlaves();
uint8_t checkSlaveTimeout();
#endif /* INC_SLAVE_MONITORING_H_ */

120
Core/Inc/main.h Normal file
View File

@ -0,0 +1,120 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.h
* @brief : Header for main.c file.
* This file contains the common defines of the application.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32g4xx_hal.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
typedef struct {
uint8_t errorcode;
uint8_t errorarg[8];
} AMSErrorHandle;
/* 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 */
void AMS_Error_Handler(AMSErrorHandle);
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
#define Slaves_Enable_Pin GPIO_PIN_13
#define Slaves_Enable_GPIO_Port GPIOC
#define BOOT0_FF_CLK_Pin GPIO_PIN_14
#define BOOT0_FF_CLK_GPIO_Port GPIOC
#define BOOT0_FF_DATA_Pin GPIO_PIN_15
#define BOOT0_FF_DATA_GPIO_Port GPIOC
#define Relay_Supply_Voltage_Pin GPIO_PIN_0
#define Relay_Supply_Voltage_GPIO_Port GPIOA
#define Pos_AIR_Current_Pin GPIO_PIN_1
#define Pos_AIR_Current_GPIO_Port GPIOA
#define Neg_AIR_Current_Pin GPIO_PIN_2
#define Neg_AIR_Current_GPIO_Port GPIOA
#define PreCharge_AIR_Current_Pin GPIO_PIN_3
#define PreCharge_AIR_Current_GPIO_Port GPIOA
#define SC_Supply_Voltage_Pin GPIO_PIN_4
#define SC_Supply_Voltage_GPIO_Port GPIOA
#define AMS_ERROR_Pin GPIO_PIN_0
#define AMS_ERROR_GPIO_Port GPIOB
#define IMD_Error_Pin GPIO_PIN_1
#define IMD_Error_GPIO_Port GPIOB
#define AMS_Error_LED_Pin GPIO_PIN_2
#define AMS_Error_LED_GPIO_Port GPIOB
#define Volt_Error_CPU_Pin GPIO_PIN_10
#define Volt_Error_CPU_GPIO_Port GPIOB
#define Positive_Side_Error_CPU_Pin GPIO_PIN_11
#define Positive_Side_Error_CPU_GPIO_Port GPIOB
#define Neg_Side_Error_CPU_Pin GPIO_PIN_12
#define Neg_Side_Error_CPU_GPIO_Port GPIOB
#define HV_Inactive_CPU_Pin GPIO_PIN_13
#define HV_Inactive_CPU_GPIO_Port GPIOB
#define Neg_AIR_Open_CPU_Pin GPIO_PIN_14
#define Neg_AIR_Open_CPU_GPIO_Port GPIOB
#define High_Side_Open_CPU_Pin GPIO_PIN_15
#define High_Side_Open_CPU_GPIO_Port GPIOB
#define Inter_STM_CS_Pin GPIO_PIN_8
#define Inter_STM_CS_GPIO_Port GPIOA
#define Inter_STM_IRQ_Pin GPIO_PIN_9
#define Inter_STM_IRQ_GPIO_Port GPIOA
#define Status_LED_Pin GPIO_PIN_10
#define Status_LED_GPIO_Port GPIOA
#define IMD_Error_LED_Pin GPIO_PIN_3
#define IMD_Error_LED_GPIO_Port GPIOB
#define PreCharge_Control_Pin GPIO_PIN_5
#define PreCharge_Control_GPIO_Port GPIOB
#define AIR_Positive_Control_Pin GPIO_PIN_6
#define AIR_Positive_Control_GPIO_Port GPIOB
#define AIR_negative_Control_Pin GPIO_PIN_7
#define AIR_negative_Control_GPIO_Port GPIOB
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
#ifdef __cplusplus
}
#endif
#endif /* __MAIN_H */

View File

@ -0,0 +1,380 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32g4xx_hal_conf.h
* @author MCD Application Team
* @brief HAL configuration file
******************************************************************************
* @attention
*
* Copyright (c) 2019 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 STM32G4xx_HAL_CONF_H
#define STM32G4xx_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_COMP_MODULE_ENABLED */
/*#define HAL_CORDIC_MODULE_ENABLED */
#define HAL_CRC_MODULE_ENABLED
/*#define HAL_CRYP_MODULE_ENABLED */
/*#define HAL_DAC_MODULE_ENABLED */
#define HAL_FDCAN_MODULE_ENABLED
/*#define HAL_FMAC_MODULE_ENABLED */
/*#define HAL_HRTIM_MODULE_ENABLED */
/*#define HAL_IRDA_MODULE_ENABLED */
/*#define HAL_IWDG_MODULE_ENABLED */
/*#define HAL_I2C_MODULE_ENABLED */
/*#define HAL_I2S_MODULE_ENABLED */
/*#define HAL_LPTIM_MODULE_ENABLED */
/*#define HAL_NAND_MODULE_ENABLED */
/*#define HAL_NOR_MODULE_ENABLED */
/*#define HAL_OPAMP_MODULE_ENABLED */
/*#define HAL_PCD_MODULE_ENABLED */
/*#define HAL_QSPI_MODULE_ENABLED */
/*#define HAL_RNG_MODULE_ENABLED */
/*#define HAL_RTC_MODULE_ENABLED */
/*#define HAL_SAI_MODULE_ENABLED */
/*#define HAL_SMARTCARD_MODULE_ENABLED */
/*#define HAL_SMBUS_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED
/*#define HAL_SRAM_MODULE_ENABLED */
/*#define HAL_TIM_MODULE_ENABLED */
/*#define HAL_UART_MODULE_ENABLED */
/*#define HAL_USART_MODULE_ENABLED */
/*#define HAL_WWDG_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
/* ########################## Register Callbacks selection ############################## */
/**
* @brief This is the list of modules where register callback can be used
*/
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U
#define USE_HAL_CORDIC_REGISTER_CALLBACKS 0U
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U
#define USE_HAL_EXTI_REGISTER_CALLBACKS 0U
#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0U
#define USE_HAL_FMAC_REGISTER_CALLBACKS 0U
#define USE_HAL_HRTIM_REGISTER_CALLBACKS 0U
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U
#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U
#define USE_HAL_UART_REGISTER_CALLBACKS 0U
#define USE_HAL_USART_REGISTER_CALLBACKS 0U
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U
/* ########################## Oscillator 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 (8000000UL) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT (100UL) /*!< 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 (16000000UL) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal High Speed oscillator (HSI48) value for USB FS and RNG.
* This internal oscillator is mainly dedicated to provide a high precision clock to
* the USB peripheral by means of a special Clock Recovery System (CRS) circuitry.
* When the CRS is not used, the HSI48 RC oscillator runs on it default frequency
* which is subject to manufacturing process variations.
*/
#if !defined (HSI48_VALUE)
#define HSI48_VALUE (48000000UL) /*!< Value of the Internal High Speed oscillator for USB FS/RNG in Hz.
The real value my vary depending on manufacturing process variations.*/
#endif /* HSI48_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
/*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations in voltage and temperature.*/
#define LSI_VALUE (32000UL) /*!< LSI Typical Value in Hz*/
#endif /* LSI_VALUE */
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE (32768UL) /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT (5000UL) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for I2S and SAI peripherals
* This value is used by the I2S and SAI HAL modules to compute the I2S and SAI clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
*/
#if !defined (EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE (12288000UL) /*!< Value of the External oscillator in Hz*/
#endif /* EXTERNAL_CLOCK_VALUE */
/* 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 (3300UL) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY (4UL) /*!< tick interrupt priority (lowest by default) */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 0U
#define INSTRUCTION_CACHE_ENABLE 1U
#define DATA_CACHE_ENABLE 1U
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* ################## SPI peripheral configuration ########################## */
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
* Activated: CRC code is present inside driver
* Deactivated: CRC code cleaned from driver
*/
#define USE_SPI_CRC 0U
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32g4xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32g4xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32g4xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32g4xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32g4xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32g4xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CORDIC_MODULE_ENABLED
#include "stm32g4xx_hal_cordic.h"
#endif /* HAL_CORDIC_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32g4xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32g4xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32g4xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32g4xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_FDCAN_MODULE_ENABLED
#include "stm32g4xx_hal_fdcan.h"
#endif /* HAL_FDCAN_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32g4xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_FMAC_MODULE_ENABLED
#include "stm32g4xx_hal_fmac.h"
#endif /* HAL_FMAC_MODULE_ENABLED */
#ifdef HAL_HRTIM_MODULE_ENABLED
#include "stm32g4xx_hal_hrtim.h"
#endif /* HAL_HRTIM_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32g4xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32g4xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32g4xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32g4xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32g4xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32g4xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32g4xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_OPAMP_MODULE_ENABLED
#include "stm32g4xx_hal_opamp.h"
#endif /* HAL_OPAMP_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32g4xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32g4xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_QSPI_MODULE_ENABLED
#include "stm32g4xx_hal_qspi.h"
#endif /* HAL_QSPI_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32g4xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32g4xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SAI_MODULE_ENABLED
#include "stm32g4xx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32g4xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32g4xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32g4xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32g4xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32g4xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32g4xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32g4xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32g4xx_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 /* STM32G4xx_HAL_CONF_H */

73
Core/Inc/stm32g4xx_it.h Normal file
View File

@ -0,0 +1,73 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32g4xx_it.h
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32G4xx_IT_H
#define __STM32G4xx_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 MemManage_Handler(void);
void BusFault_Handler(void);
void UsageFault_Handler(void);
void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void DMA1_Channel2_IRQHandler(void);
void ADC1_2_IRQHandler(void);
void FDCAN1_IT0_IRQHandler(void);
void FDCAN1_IT1_IRQHandler(void);
void SPI1_IRQHandler(void);
void DMA2_Channel1_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __STM32G4xx_IT_H */

View File

@ -0,0 +1,231 @@
/*
* AIR_State_Maschine.c
*
* Created on: Jun 15, 2022
* Author: max
*/
#include "AIR_State_Maschine.h"
ADC_HandleTypeDef* air_current_adc = {0};
ADC_HandleTypeDef* sdc_voltage_adc = {0};
DMA_HandleTypeDef* air_current_dma = {0};
DMA_HandleTypeDef* sdc_voltage_dma = {0};
uint8_t air_adc_complete = 0;
uint8_t sdc_adc_complete = 0;
AIRStateHandler init_AIR_State_Maschine(ADC_HandleTypeDef* relay_adc,
ADC_HandleTypeDef* sc_adc,
DMA_HandleTypeDef* relay_dma,
DMA_HandleTypeDef* sc_dma) {
air_current_adc = relay_adc;
sdc_voltage_adc = sc_adc;
air_current_dma = relay_dma;
sdc_voltage_dma = sc_dma;
AIRStateHandler airstate = {0};
airstate.targetTSState = TS_INACTIVE;
airstate.currentTSState = TS_INACTIVE;
airstate.ShutdownCircuitVoltage = 0;
airstate.RelaisSupplyVoltage = 0;
airstate.AIRNegativeCurrent = 0;
airstate.AIRPositiveCurrent = 0;
airstate.AIRPrechargeCurrent = 0;
airstate.BatteryVoltageBatterySide = 0;
airstate.BatteryVoltageVehicleSide = 0;
return airstate;
}
void Update_AIR_Info(AIRStateHandler* airstate) {
uint16_t relay_adc_buffer[4] = {0};
uint16_t sdc_adc_buffer[1] = {0};
/*//HAL_ADC_Start_DMA(air_current_adc, (uint32_t*)relay_adc_buffer, 4);
//HAL_ADC_Start_DMA(sdc_voltage_adc, (uint32_t*)sdc_adc_buffer, 1);
HAL_ADC_Start(sdc_voltage_adc);
HAL_StatusTypeDef status = HAL_ADC_PollForConversion(sdc_voltage_adc, 10);
uint32_t adcval1 = HAL_ADC_GetValue(sdc_voltage_adc);
HAL_ADC_Stop(sdc_voltage_adc);
HAL_ADC_Start(air_current_adc);
status = HAL_ADC_PollForConversion(air_current_adc, 10);
uint32_t adcval2 = HAL_ADC_GetValue(air_current_adc);
HAL_ADC_Start(air_current_adc);
status = HAL_ADC_PollForConversion(air_current_adc, 10);
uint32_t adcval3 = HAL_ADC_GetValue(air_current_adc);
HAL_ADC_Start(air_current_adc);
status = HAL_ADC_PollForConversion(air_current_adc, 10);
uint32_t adcval4 = HAL_ADC_GetValue(air_current_adc);
HAL_ADC_Start(air_current_adc);
status = HAL_ADC_PollForConversion(air_current_adc, 10);
uint32_t adcval5 = HAL_ADC_GetValue(air_current_adc);
HAL_ADC_Stop(air_current_adc);*/
uint32_t startmils = HAL_GetTick() + ADC_READ_TIMEOUT;
{
airstate->RelaisSupplyVoltage = 3000;
airstate->AIRPositiveCurrent = 0;
airstate->AIRNegativeCurrent = 0;
airstate->AIRPrechargeCurrent = 0;
airstate->ShutdownCircuitVoltage = 3000;
}
}
uint8_t Update_AIR_State(AIRStateHandler* airstate) {
Update_AIR_Info(airstate);
//--------------------------------------------------State Transition
// Rules----------------------------------------------------------
/*if(airstate->currentTSState == airstate->targetTSState) //Target TS
State is Equal to actual TS State
{
return airstate->currentTSState;
}*/
if (airstate->currentTSState == TS_ERROR) // No Escape from TS Error State
{
return TS_ERROR;
}
else if ((airstate->currentTSState == TS_INACTIVE) &&
(airstate->targetTSState ==
TS_ACTIVE)) // Transition from Inactive to Active via Precharge
{
if ((airstate->RelaisSupplyVoltage) > SDC_LOWER_THRESHOLD) {
airstate->currentTSState = TS_PRECHARGE;
}
}
// TODO: Is it correct that we also go from precharge to discharge?
else if ((airstate->currentTSState == TS_ACTIVE ||
airstate->currentTSState == TS_PRECHARGE) &&
(airstate->targetTSState ==
TS_INACTIVE)) // Transition from Active to Inactive via Discharge
{
airstate->currentTSState = TS_DISCHARGE;
}
else if (airstate->targetTSState ==
TS_ERROR) // Error State is Entered if Target State is Error State
{
airstate->currentTSState = TS_ERROR;
}
else if (airstate->currentTSState ==
TS_PRECHARGE) // Change from Precharge to Active at 95% TS Voltage at
// Vehicle Side
{
if ((airstate->BatteryVoltageVehicleSide >
LOWER_VEHICLE_SIDE_VOLTAGE_LIMIT)) {
if (airstate->BatteryVoltageVehicleSide >
(airstate->BatteryVoltageBatterySide * 0.90)) {
airstate->currentTSState = TS_ACTIVE;
}
}
}
else if (airstate->currentTSState ==
TS_DISCHARGE) // Change from Discharge to Inactive at 95% TS Voltage
// at Vehicle Side
{
airstate->currentTSState = TS_INACTIVE;
}
//_-----------------------------------------------AIR
// Positions--------------------------------------------------------
if (airstate->currentTSState == TS_PRECHARGE) {
AIR_Precharge_Position();
}
if (airstate->currentTSState == TS_DISCHARGE) {
AIR_Discharge_Position();
}
if (airstate->currentTSState == TS_ACTIVE) {
AIR_Active_Position();
}
if (airstate->currentTSState == TS_INACTIVE) {
AIR_Inactive_Position();
}
if (airstate->currentTSState == TS_ERROR) {
AIR_Error_Position();
}
return airstate->currentTSState;
}
void Activate_TS(AIRStateHandler* airstate) {
airstate->targetTSState = TS_ACTIVE;
}
void Deactivate_TS(AIRStateHandler* airstate) {
airstate->targetTSState = TS_INACTIVE;
}
void AIR_Precharge_Position() {
HAL_GPIO_WritePin(PreCharge_Control_GPIO_Port, PreCharge_Control_Pin,
GPIO_PIN_SET);
HAL_GPIO_WritePin(AIR_negative_Control_GPIO_Port, AIR_negative_Control_Pin,
GPIO_PIN_SET);
HAL_GPIO_WritePin(AIR_Positive_Control_GPIO_Port, AIR_Positive_Control_Pin,
GPIO_PIN_RESET);
}
void AIR_Inactive_Position() {
HAL_GPIO_WritePin(PreCharge_Control_GPIO_Port, PreCharge_Control_Pin,
GPIO_PIN_RESET);
HAL_GPIO_WritePin(AIR_negative_Control_GPIO_Port, AIR_negative_Control_Pin,
GPIO_PIN_RESET);
HAL_GPIO_WritePin(AIR_Positive_Control_GPIO_Port, AIR_Positive_Control_Pin,
GPIO_PIN_RESET);
}
void AIR_Discharge_Position() {
HAL_GPIO_WritePin(PreCharge_Control_GPIO_Port, PreCharge_Control_Pin,
GPIO_PIN_SET);
HAL_GPIO_WritePin(AIR_negative_Control_GPIO_Port, AIR_negative_Control_Pin,
GPIO_PIN_SET);
HAL_GPIO_WritePin(AIR_Positive_Control_GPIO_Port, AIR_Positive_Control_Pin,
GPIO_PIN_RESET);
}
void AIR_Active_Position() // TODO Deactivate Precharge after a while to
// decrease current Consumption
{
HAL_GPIO_WritePin(PreCharge_Control_GPIO_Port, PreCharge_Control_Pin,
GPIO_PIN_SET);
HAL_GPIO_WritePin(AIR_negative_Control_GPIO_Port, AIR_negative_Control_Pin,
GPIO_PIN_SET);
HAL_GPIO_WritePin(AIR_Positive_Control_GPIO_Port, AIR_Positive_Control_Pin,
GPIO_PIN_SET);
}
void AIR_Error_Position() {
HAL_GPIO_WritePin(PreCharge_Control_GPIO_Port, PreCharge_Control_Pin,
GPIO_PIN_RESET);
HAL_GPIO_WritePin(AIR_negative_Control_GPIO_Port, AIR_negative_Control_Pin,
GPIO_PIN_RESET);
HAL_GPIO_WritePin(AIR_Positive_Control_GPIO_Port, AIR_Positive_Control_Pin,
GPIO_PIN_RESET);
}
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc) {
if (hadc == air_current_adc) {
air_adc_complete = 1;
HAL_ADC_Stop_DMA(air_current_adc);
}
if (hadc == sdc_voltage_adc) {
sdc_adc_complete = 1;
HAL_ADC_Stop_DMA(sdc_voltage_adc);
}
}

View File

@ -0,0 +1,212 @@
/*
* CAN_Communication.c
*
* Created on: Apr 26, 2022
* Author: max
*/
#include "CAN_Communication.h"
#include "Error_Check.h"
#include "stm32g4xx_hal_fdcan.h"
const uint16_t slave_CAN_id_to_slave_index[7] = {
0, 1, 2, 3, 255, 5, 4}; // TODO: Make this pretty pls
canFrame framebuffer[CANFRAMEBUFFERSIZE] = {0};
uint8_t framebufferwritepointer;
uint8_t framebufferreadpointer;
void CAN_Init(FDCAN_HandleTypeDef* hcan) {
HAL_FDCAN_Stop(hcan);
framebufferreadpointer = 0;
framebufferwritepointer = 0;
FDCAN_FilterTypeDef fdfilter = {0};
fdfilter.FilterConfig = FDCAN_FILTER_TO_RXFIFO0;
fdfilter.FilterID1 = 0x000; // Range start
fdfilter.FilterID2 = 0x000; // Range stop
fdfilter.FilterIndex = 0;
fdfilter.FilterType = FDCAN_FILTER_MASK;
fdfilter.IdType = FDCAN_STANDARD_ID;
HAL_FDCAN_ConfigFilter(hcan, &fdfilter);
HAL_StatusTypeDef status = HAL_FDCAN_Start(hcan);
status =
HAL_FDCAN_ActivateNotification(hcan, FDCAN_IT_RX_FIFO0_NEW_MESSAGE, 0);
}
uint8_t CAN_Receive(FDCAN_HandleTypeDef* hcan) {
while (framebufferreadpointer != framebufferwritepointer) {
framebufferreadpointer++;
if (framebufferreadpointer >= CANFRAMEBUFFERSIZE) {
framebufferreadpointer = 0;
}
canFrame rxFrame = framebuffer[framebufferreadpointer];
if ((rxFrame.FrameID & SLAVE_STATUS_BASE_ADDRESS) ==
SLAVE_STATUS_BASE_ADDRESS) {
uint16_t msg = rxFrame.FrameID - SLAVE_STATUS_BASE_ADDRESS;
uint8_t slaveID = (msg & 0x0F0) >> 4;
slaveID = slave_CAN_id_to_slave_index[slaveID];
uint8_t messageID = msg & 0x00F;
updateSlaveInfo(slaveID, messageID, rxFrame);
}
/* if(rxFrame.FrameID == SLAVE_EMERGENCY_ADDRESS)
{
AMSErrorHandle errorframe = {0};
errorframe.errorcode = SlavesErrorFrameError;
errorframe.errorarg[0] = rxFrame.data[0];
errorframe.errorarg[1] = rxFrame.data[1];
errorframe.errorarg[2] = rxFrame.data[2];
errorframe.errorarg[3] = rxFrame.data[3];
errorframe.errorarg[4] = rxFrame.data[4];
errorframe.errorarg[5] = rxFrame.data[5];
errorframe.errorarg[6] = rxFrame.data[6];
errorframe.errorarg[7] = rxFrame.data[7];
AMS_Error_Handler(errorframe);
}*/
}
return 0;
}
uint8_t CAN_Transmit(FDCAN_HandleTypeDef* hcan, uint16_t frameid,
uint8_t* buffer, uint8_t datalen) {
FDCAN_TxHeaderTypeDef txheader = {0};
txheader.Identifier = frameid;
txheader.IdType = FDCAN_STANDARD_ID;
txheader.TxFrameType = FDCAN_FRAME_CLASSIC;
txheader.DataLength = ((uint32_t)datalen) << 16;
txheader.ErrorStateIndicator = FDCAN_ESI_ACTIVE;
txheader.BitRateSwitch = FDCAN_BRS_OFF;
txheader.FDFormat = FDCAN_CLASSIC_CAN;
txheader.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
txheader.MessageMarker = 0;
HAL_FDCAN_AddMessageToTxFifoQ(hcan, &txheader, buffer);
return 0;
}
void HAL_FDCAN_ErrorCallback(FDCAN_HandleTypeDef* hcan) {}
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef* handle,
uint32_t interrupt_flags) {
FDCAN_RxHeaderTypeDef rxFrameHeader;
uint8_t data[8];
framebufferwritepointer++;
if (framebufferwritepointer >= CANFRAMEBUFFERSIZE) {
framebufferwritepointer = 0;
}
if (!(interrupt_flags & FDCAN_IT_RX_FIFO0_NEW_MESSAGE)) {
return;
}
if (HAL_FDCAN_GetRxMessage(handle, FDCAN_RX_FIFO0, &rxFrameHeader, data) !=
HAL_OK) {
framebuffer[framebufferwritepointer].error = 1;
} else {
framebuffer[framebufferwritepointer].error = 0;
}
if (rxFrameHeader.IdType != FDCAN_STANDARD_ID) {
return;
}
framebuffer[framebufferwritepointer].FrameID =
(int16_t)rxFrameHeader.Identifier;
framebuffer[framebufferwritepointer].length =
(uint8_t)rxFrameHeader.DataLength >> 16;
for (int i = 0; i < (rxFrameHeader.DataLength >> 16); i++) {
framebuffer[framebufferwritepointer].data[i] = data[i];
}
framebuffer[framebufferwritepointer].timestamp = HAL_GetTick();
}
void updateSlaveInfo(uint8_t slaveID, uint8_t MessageID, canFrame rxFrame) {
if (slaveID < NUMBEROFSLAVES) {
switch (MessageID) {
case 0x00:
slaves[slaveID].cellVoltages[0] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellVoltages[1] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellVoltages[2] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellVoltages[3] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x01:
slaves[slaveID].cellVoltages[4] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellVoltages[5] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellVoltages[6] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellVoltages[7] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x02:
slaves[slaveID].cellVoltages[8] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellVoltages[9] = rxFrame.data[2] | rxFrame.data[3] << 8;
break;
case 0x03:
slaves[slaveID].cellTemps[0] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellTemps[1] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellTemps[2] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellTemps[3] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x04:
slaves[slaveID].cellTemps[4] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellTemps[5] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellTemps[6] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellTemps[7] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x05:
slaves[slaveID].cellTemps[8] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellTemps[9] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellTemps[10] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellTemps[11] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x06:
slaves[slaveID].cellTemps[12] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellTemps[13] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellTemps[14] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellTemps[15] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x07:
slaves[slaveID].cellTemps[16] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellTemps[17] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellTemps[18] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellTemps[19] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x08:
slaves[slaveID].cellTemps[20] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellTemps[21] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellTemps[22] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellTemps[23] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x09:
slaves[slaveID].cellTemps[24] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellTemps[25] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellTemps[26] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellTemps[27] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
case 0x0A:
slaves[slaveID].cellTemps[28] = rxFrame.data[0] | rxFrame.data[1] << 8;
slaves[slaveID].cellTemps[29] = rxFrame.data[2] | rxFrame.data[3] << 8;
slaves[slaveID].cellTemps[30] = rxFrame.data[4] | rxFrame.data[5] << 8;
slaves[slaveID].cellTemps[31] = rxFrame.data[6] | rxFrame.data[7] << 8;
break;
}
slaves[slaveID].timestamp = rxFrame.timestamp;
}
}

32
Core/Src/Error_Check.c Normal file
View File

@ -0,0 +1,32 @@
/*
* Error_Check.c
*
* Created on: Jun 16, 2022
* Author: max
*/
#include "Error_Check.h"
ErrorFlags CheckErrorFlags() {
ErrorFlags errors = {0};
errors.IMD_ERROR = !HAL_GPIO_ReadPin(IMD_Error_GPIO_Port, IMD_Error_Pin);
errors.IMD_ERROR_LED =
HAL_GPIO_ReadPin(IMD_Error_LED_GPIO_Port, IMD_Error_LED_Pin);
errors.AMS_ERROR_LED =
HAL_GPIO_ReadPin(AMS_ERROR_GPIO_Port, AMS_Error_LED_Pin);
errors.TS_no_voltage_error =
HAL_GPIO_ReadPin(Volt_Error_CPU_GPIO_Port, Volt_Error_CPU_Pin);
errors.positive_AIR_or_PC_error = HAL_GPIO_ReadPin(
Positive_Side_Error_CPU_GPIO_Port, Positive_Side_Error_CPU_Pin);
errors.negative_AIR_error =
HAL_GPIO_ReadPin(Neg_Side_Error_CPU_GPIO_Port, Neg_Side_Error_CPU_Pin);
errors.HV_inactive =
HAL_GPIO_ReadPin(HV_Inactive_CPU_GPIO_Port, HV_Inactive_CPU_Pin);
errors.negative_AIR_open =
HAL_GPIO_ReadPin(Neg_AIR_Open_CPU_GPIO_Port, Neg_AIR_Open_CPU_Pin);
errors.positive_AIR_and_PC_open =
HAL_GPIO_ReadPin(High_Side_Open_CPU_GPIO_Port, High_Side_Open_CPU_Pin);
return errors;
}

View File

@ -0,0 +1,391 @@
/*
* SPI_Slave_Communication.c
*
* Created on: Jun 16, 2022
* Author: max
*/
#include "SPI_Slave_Communication.h"
#include "stm32g4xx_hal.h"
#include "stm32g4xx_hal_crc.h"
#include "stm32g4xx_hal_def.h"
#include "stm32g4xx_hal_spi.h"
#include "stm32g4xx_hal_spi_ex.h"
#include <stdint.h>
#define SPI_BUFFER_SIZE 1024
#define DUMMYBYTES 2
#define SPI_TIMEOUT 10
SPI_HandleTypeDef* spibus;
extern ErrorFlags errorflags;
uint8_t spirxbuf[SPI_BUFFER_SIZE];
uint8_t spitxbuf[SPI_BUFFER_SIZE];
static volatile int spi_transfer_complete;
uint8_t command;
AIRStateHandler* spi_airstates;
AMSErrorHandle* spierrorinfo;
void set_SPI_errorInfo(AMSErrorHandle* errorinfo) {
spierrorinfo = errorinfo;
spierrorinfo->errorcode = 0;
spierrorinfo->errorarg[0] = 0;
spierrorinfo->errorarg[1] = 0;
spierrorinfo->errorarg[2] = 0;
spierrorinfo->errorarg[3] = 0;
spierrorinfo->errorarg[4] = 0;
spierrorinfo->errorarg[5] = 0;
spierrorinfo->errorarg[6] = 0;
spierrorinfo->errorarg[7] = 0;
}
void spi_communication_init(SPI_HandleTypeDef* spi,
AIRStateHandler* airstatemaschine) {
spibus = spi;
spi_airstates = airstatemaschine;
command = 0xFF;
HAL_SPI_DeInit(spi);
// HAL_SPI_Receive_IT(spibus, &command, 1);
}
// void setShuntdata() {
// uint8_t status = receiveData(12);
// if (status == HAL_OK) {
// spi_airstates->BatteryVoltageBatterySide =
// spirxbuf[0] << 24 | spirxbuf[1] << 16 | spirxbuf[2] << 8 |
// spirxbuf[3];
// spi_airstates->BatteryVoltageVehicleSide =
// spirxbuf[4] << 24 | spirxbuf[5] << 16 | spirxbuf[6] << 8 |
// spirxbuf[7];
// uint32_t current = spirxbuf[8] << 24 | spirxbuf[9] << 16 |
// spirxbuf[10] << 8 | spirxbuf[11];
// }
// }
// void setTSState() {
// uint8_t status = receiveData(1);
// if (status == HAL_OK) {
// spi_airstates->targetTSState = spirxbuf[0];
// }
// }
// void getTSState() {
// spitxbuf[0] = spi_airstates->currentTSState;
// spitxbuf[1] = (uint8_t)(spi_airstates->targetTSState);
// spitxbuf[2] = (uint8_t)(spi_airstates->RelaisSupplyVoltage >> 8) & 0xFF;
// spitxbuf[3] = (uint8_t)(spi_airstates->RelaisSupplyVoltage & 0xFF);
// spitxbuf[4] = (uint8_t)((spi_airstates->ShutdownCircuitVoltage >> 8) &
// 0xFF); spitxbuf[5] = (uint8_t)(spi_airstates->ShutdownCircuitVoltage &
// 0xFF); spitxbuf[6] = (uint8_t)((spi_airstates->AIRNegativeCurrent >> 8) &
// 0xFF); spitxbuf[7] = (uint8_t)(spi_airstates->AIRNegativeCurrent & 0xFF);
// spitxbuf[8] = (uint8_t)((spi_airstates->AIRPositiveCurrent >> 8) & 0xFF);
// spitxbuf[9] = (uint8_t)((spi_airstates->AIRPositiveCurrent) & 0xFF);
// spitxbuf[10] = (uint8_t)((spi_airstates->AIRPrechargeCurrent >> 8) & 0xFF);
// spitxbuf[11] = (uint8_t)((spi_airstates->AIRPrechargeCurrent) & 0xFF);
// spitxbuf[12] =
// (uint8_t)((spi_airstates->BatteryVoltageBatterySide >> 24) & 0xFF);
// spitxbuf[13] =
// (uint8_t)((spi_airstates->BatteryVoltageBatterySide >> 16) & 0xFF);
// spitxbuf[14] =
// (uint8_t)((spi_airstates->BatteryVoltageBatterySide >> 8) & 0xFF);
// spitxbuf[15] =
// (uint8_t)((spi_airstates->BatteryVoltageBatterySide >> 0) & 0xFF);
// spitxbuf[16] =
// (uint8_t)((spi_airstates->BatteryVoltageVehicleSide >> 24) & 0xFF);
// spitxbuf[17] =
// (uint8_t)((spi_airstates->BatteryVoltageVehicleSide >> 16) & 0xFF);
// spitxbuf[18] =
// (uint8_t)((spi_airstates->BatteryVoltageVehicleSide >> 8) & 0xFF);
// spitxbuf[19] =
// (uint8_t)((spi_airstates->BatteryVoltageVehicleSide >> 0) & 0xFF);
// transmitData(20);
// }
// void getError() {
// spitxbuf[0] = spierrorinfo->errorcode;
// spitxbuf[1] = spierrorinfo->errorarg[0];
// spitxbuf[2] = spierrorinfo->errorarg[1];
// spitxbuf[3] = spierrorinfo->errorarg[2];
// spitxbuf[4] = spierrorinfo->errorarg[3];
// spitxbuf[5] = spierrorinfo->errorarg[4];
// spitxbuf[6] = spierrorinfo->errorarg[5];
// spitxbuf[7] = spierrorinfo->errorarg[6];
// spitxbuf[8] = spierrorinfo->errorarg[7];
// spitxbuf[9] = (errorflags.AMS_ERROR_LED << 7) |
// (errorflags.IMD_ERROR_LED << 6) | (errorflags.IMD_ERROR << 5)
// | (errorflags.HV_inactive << 4) |
// (errorflags.TS_no_voltage_error << 3) |
// (errorflags.negative_AIR_error << 2) |
// (errorflags.positive_AIR_or_PC_error << 1) |
// (errorflags.positive_AIR_and_PC_open);
// spitxbuf[10] = (errorflags.negative_AIR_open);
// spitxbuf[11] = calculateChecksum(spitxbuf, 10);
// transmitData(12);
// }
// void togglestatusLED() {
// HAL_GPIO_TogglePin(Status_LED_GPIO_Port, Status_LED_Pin);
// }
// void getMeasurements() {
// for (int n = 0; n < NUMBEROFSLAVES; n++) {
// spitxbuf[n * 89] = slaves[n].slaveID;
// spitxbuf[n * 89 + 1] = (uint8_t)((slaves[n].timestamp >> 24) & 0xFF);
// spitxbuf[n * 89 + 2] = (uint8_t)((slaves[n].timestamp >> 16) & 0xFF);
// spitxbuf[n * 89 + 3] = (uint8_t)((slaves[n].timestamp >> 8) & 0xFF);
// spitxbuf[n * 89 + 4] = (uint8_t)((slaves[n].timestamp >> 0) & 0xFF);
// for (int i = 0; i < NUMBEROFCELLS; i++) {
// spitxbuf[n * 89 + 5 + 2 * i] =
// (uint8_t)((slaves[n].cellVoltages[i] >> 8) & 0xFF);
// spitxbuf[n * 89 + 6 + 2 * i] =
// (uint8_t)((slaves[n].cellVoltages[i]) & 0xFF);
// }
// for (int i = 0; i < NUMBEROFTEMPS; i++) {
// spitxbuf[n * 89 + 25 + 2 * i] =
// (uint8_t)((slaves[n].cellTemps[i] >> 8) & 0xFF);
// spitxbuf[n * 89 + 26 + 2 * i] =
// (uint8_t)((slaves[n].cellTemps[i]) & 0xFF);
// }
// }
// transmitData(NUMBEROFSLAVES * 89);
// }
// uint8_t receiveData(uint16_t length) {
// if (length > 1024)
// return 0xFF;
// HAL_GPIO_WritePin(Inter_STM_IRQ_GPIO_Port, Inter_STM_IRQ_Pin,
// GPIO_PIN_SET); HAL_StatusTypeDef status =
// HAL_SPI_Receive(spibus, spirxbuf, length, SPI_TIMEOUT);
// HAL_GPIO_WritePin(Inter_STM_IRQ_GPIO_Port, Inter_STM_IRQ_Pin,
// GPIO_PIN_RESET); return (uint8_t)status;
// }
// uint8_t transmitData(uint16_t length) {
// if (length > 1024)
// return 0xFF;
// HAL_GPIO_WritePin(Inter_STM_IRQ_GPIO_Port, Inter_STM_IRQ_Pin,
// GPIO_PIN_SET); HAL_StatusTypeDef status =
// HAL_SPI_Transmit(spibus, spitxbuf, length, SPI_TIMEOUT);
// HAL_GPIO_WritePin(Inter_STM_IRQ_GPIO_Port, Inter_STM_IRQ_Pin,
// GPIO_PIN_RESET); return (uint8_t)status;
// }
void checkSPI() {
/*
if(commandreceived)
{
commandreceived = 0;
switch(command)
{
case SET_SHUNTDATA:
setShuntdata();
break;
case SET_TSSTATE:
setTSState();
break;
case GET_TSSTATE:
getTSState();
break;
case GET_ERROR:
getError();
break;
case TOGGLE_STATUS_LED:
togglestatusLED();
break;
case GET_MEASUREMENTS:
getMeasurements();
break;
default:
break;
}
HAL_SPI_Receive_IT(spibus, &command, 1);
}
else
{
if(spibus->State == HAL_SPI_STATE_READY)
{
HAL_SPI_Receive_IT(spibus, &command, 1);
}
}
*/
InterSTMFrame();
}
// uint8_t checkXor(uint8_t *buf, uint8_t len) {
// uint8_t checksum = 0xFF;
// for (int i = 0; i < len; i++) {
// checksum ^= buf[i];
// }
// if (checksum == buf[len]) {
// return 0;
// } else {
// return 1;
// }
// }
uint8_t calculateChecksum(uint8_t* buf, uint8_t len) {
uint8_t checksum = 0xFF;
for (int i = 0; i < len; i++) {
checksum ^= buf[i];
}
return checksum;
}
void InterSTMFrame() {
HAL_GPIO_TogglePin(Status_LED_GPIO_Port, Status_LED_Pin);
if (HAL_GPIO_ReadPin(Inter_STM_CS_GPIO_Port, Inter_STM_CS_Pin) ==
GPIO_PIN_RESET) {
return;
}
for (int n = 0; n < NUMBEROFSLAVES; n++) {
spitxbuf[n * 89] = slaves[n].slaveID;
spitxbuf[n * 89 + 1] = (uint8_t)((slaves[n].timestamp >> 24) & 0xFF);
spitxbuf[n * 89 + 2] = (uint8_t)((slaves[n].timestamp >> 16) & 0xFF);
spitxbuf[n * 89 + 3] = (uint8_t)((slaves[n].timestamp >> 8) & 0xFF);
spitxbuf[n * 89 + 4] = (uint8_t)((slaves[n].timestamp >> 0) & 0xFF);
for (int i = 0; i < NUMBEROFCELLS; i++) {
spitxbuf[n * 89 + 5 + 2 * i] =
(uint8_t)((slaves[n].cellVoltages[i] >> 8) & 0xFF);
spitxbuf[n * 89 + 6 + 2 * i] =
(uint8_t)((slaves[n].cellVoltages[i]) & 0xFF);
}
for (int i = 0; i < NUMBEROFTEMPS; i++) {
spitxbuf[n * 89 + 25 + 2 * i] =
(uint8_t)((slaves[n].cellTemps[i] >> 8) & 0xFF);
spitxbuf[n * 89 + 26 + 2 * i] =
(uint8_t)((slaves[n].cellTemps[i]) & 0xFF);
}
}
uint16_t errorcodebaseaddress = NUMBEROFSLAVES * 89 + 1;
spitxbuf[errorcodebaseaddress + 0] = spierrorinfo->errorcode;
spitxbuf[errorcodebaseaddress + 1] = spierrorinfo->errorarg[0];
spitxbuf[errorcodebaseaddress + 2] = spierrorinfo->errorarg[1];
spitxbuf[errorcodebaseaddress + 3] = spierrorinfo->errorarg[2];
spitxbuf[errorcodebaseaddress + 4] = spierrorinfo->errorarg[3];
spitxbuf[errorcodebaseaddress + 5] = spierrorinfo->errorarg[4];
spitxbuf[errorcodebaseaddress + 6] = spierrorinfo->errorarg[5];
spitxbuf[errorcodebaseaddress + 7] = spierrorinfo->errorarg[6];
spitxbuf[errorcodebaseaddress + 8] = spierrorinfo->errorarg[7];
spitxbuf[errorcodebaseaddress + 9] =
(errorflags.AMS_ERROR_LED << 7) | (errorflags.IMD_ERROR_LED << 6) |
(errorflags.IMD_ERROR << 5) | (errorflags.HV_inactive << 4) |
(errorflags.TS_no_voltage_error << 3) |
(errorflags.negative_AIR_error << 2) |
(errorflags.positive_AIR_or_PC_error << 1) |
(errorflags.positive_AIR_and_PC_open);
spitxbuf[errorcodebaseaddress + 10] = (errorflags.negative_AIR_open);
spitxbuf[errorcodebaseaddress + 11] = calculateChecksum(spitxbuf, 10);
uint16_t tsstatebaseaddress = errorcodebaseaddress + 12;
spitxbuf[tsstatebaseaddress + 0] = spi_airstates->currentTSState;
spitxbuf[tsstatebaseaddress + 1] = (uint8_t)(spi_airstates->targetTSState);
spitxbuf[tsstatebaseaddress + 2] =
(uint8_t)(spi_airstates->RelaisSupplyVoltage >> 8) & 0xFF;
spitxbuf[tsstatebaseaddress + 3] =
(uint8_t)(spi_airstates->RelaisSupplyVoltage & 0xFF);
spitxbuf[tsstatebaseaddress + 4] =
(uint8_t)((spi_airstates->ShutdownCircuitVoltage >> 8) & 0xFF);
spitxbuf[tsstatebaseaddress + 5] =
(uint8_t)(spi_airstates->ShutdownCircuitVoltage & 0xFF);
spitxbuf[tsstatebaseaddress + 6] =
(uint8_t)((spi_airstates->AIRNegativeCurrent >> 8) & 0xFF);
spitxbuf[tsstatebaseaddress + 7] =
(uint8_t)(spi_airstates->AIRNegativeCurrent & 0xFF);
spitxbuf[tsstatebaseaddress + 8] =
(uint8_t)((spi_airstates->AIRPositiveCurrent >> 8) & 0xFF);
spitxbuf[tsstatebaseaddress + 9] =
(uint8_t)((spi_airstates->AIRPositiveCurrent) & 0xFF);
spitxbuf[tsstatebaseaddress + 10] =
(uint8_t)((spi_airstates->AIRPrechargeCurrent >> 8) & 0xFF);
spitxbuf[tsstatebaseaddress + 11] =
(uint8_t)((spi_airstates->AIRPrechargeCurrent) & 0xFF);
spitxbuf[tsstatebaseaddress + 12] =
(uint8_t)((spi_airstates->BatteryVoltageBatterySide >> 24) & 0xFF);
spitxbuf[tsstatebaseaddress + 13] =
(uint8_t)((spi_airstates->BatteryVoltageBatterySide >> 16) & 0xFF);
spitxbuf[tsstatebaseaddress + 14] =
(uint8_t)((spi_airstates->BatteryVoltageBatterySide >> 8) & 0xFF);
spitxbuf[tsstatebaseaddress + 15] =
(uint8_t)((spi_airstates->BatteryVoltageBatterySide >> 0) & 0xFF);
spitxbuf[tsstatebaseaddress + 16] =
(uint8_t)((spi_airstates->BatteryVoltageVehicleSide >> 24) & 0xFF);
spitxbuf[tsstatebaseaddress + 17] =
(uint8_t)((spi_airstates->BatteryVoltageVehicleSide >> 16) & 0xFF);
spitxbuf[tsstatebaseaddress + 18] =
(uint8_t)((spi_airstates->BatteryVoltageVehicleSide >> 8) & 0xFF);
spitxbuf[tsstatebaseaddress + 19] =
(uint8_t)((spi_airstates->BatteryVoltageVehicleSide >> 0) & 0xFF);
uint32_t spitimeoutcounter = HAL_GetTick();
HAL_SPI_DeInit(spibus);
HAL_SPI_Init(spibus);
HAL_SPIEx_FlushRxFifo(spibus);
spi_transfer_complete = 0;
HAL_SPI_Receive_IT(spibus, spirxbuf, 13);
HAL_GPIO_WritePin(Inter_STM_IRQ_GPIO_Port, Inter_STM_IRQ_Pin, GPIO_PIN_SET);
uint32_t timeout = HAL_GetTick() + 500;
while (!spi_transfer_complete && HAL_GetTick() < timeout) {
}
HAL_GPIO_WritePin(Inter_STM_IRQ_GPIO_Port, Inter_STM_IRQ_Pin, GPIO_PIN_RESET);
if (!spi_transfer_complete) {
HAL_SPI_Abort(spibus);
return;
}
spi_airstates->BatteryVoltageBatterySide =
spirxbuf[0] << 24 | spirxbuf[1] << 16 | spirxbuf[2] << 8 | spirxbuf[3];
spi_airstates->BatteryVoltageVehicleSide =
spirxbuf[4] << 24 | spirxbuf[5] << 16 | spirxbuf[6] << 8 | spirxbuf[7];
uint32_t current =
spirxbuf[8] << 24 | spirxbuf[9] << 16 | spirxbuf[10] << 8 | spirxbuf[11];
spi_airstates->targetTSState = spirxbuf[12];
}
void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef* hspi) {
HAL_SPI_Transmit_IT(spibus, spitxbuf, NUMBEROFSLAVES * 89 + 33);
}
void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef* hspi) {
spi_transfer_complete = 1;
}
// void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi) {
// __HAL_SPI_CLEAR_OVRFLAG(hspi);
// // HAL_SPI_Receive_IT(spibus, &command, 1);
// HAL_SPIEx_FlushRxFifo(hspi);
// }

View File

@ -0,0 +1,57 @@
/*
* Slave_Monitoring.c
*
* Created on: Jun 15, 2022
* Author: max
*/
#include "Slave_Monitoring.h"
SlaveHandler slaves[NUMBEROFSLAVES];
void initSlaves() {
HAL_GPIO_WritePin(Slaves_Enable_GPIO_Port, Slaves_Enable_Pin, GPIO_PIN_RESET);
HAL_GPIO_WritePin(BOOT0_FF_DATA_GPIO_Port, BOOT0_FF_DATA_Pin, GPIO_PIN_RESET);
for (int i = 0; i < NUMBEROFSLAVES + 5; i++) {
HAL_GPIO_WritePin(BOOT0_FF_CLK_GPIO_Port, BOOT0_FF_CLK_Pin, GPIO_PIN_SET);
HAL_Delay(1);
HAL_GPIO_WritePin(BOOT0_FF_CLK_GPIO_Port, BOOT0_FF_CLK_Pin, GPIO_PIN_RESET);
HAL_Delay(1);
}
HAL_Delay(5);
HAL_GPIO_WritePin(Slaves_Enable_GPIO_Port, Slaves_Enable_Pin, GPIO_PIN_SET);
for (int n = 0; n < NUMBEROFSLAVES; n++) {
for (int i = 0; i < NUMBEROFTEMPS; i++)
slaves[n].cellTemps[i] = 30000;
for (int j = 0; j < NUMBEROFCELLS; j++)
slaves[n].cellVoltages[j] = 25000;
slaves[n].error = 0;
slaves[n].timeout = 0;
slaves[n].timestamp = HAL_GetTick();
slaves[n].slaveID = n;
}
}
uint8_t checkSlaveTimeout() {
if (HAL_GetTick() < 10000) {
return 0;
}
for (int n = 0; n < NUMBEROFSLAVES; n++) {
if (((int)(HAL_GetTick() - slaves[n].timestamp)) > SLAVETIMEOUT) {
slaves[n].timeout = 1;
AMSErrorHandle timeouterror;
timeouterror.errorcode = SlavesTimeoutError;
AMS_Error_Handler(timeouterror);
return 1;
}
}
return 0;
}

588
Core/Src/main.c Normal file
View File

@ -0,0 +1,588 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "AIR_State_Maschine.h"
#include "AMS_Errorcodes.h"
#include "CAN_Communication.h"
#include "Error_Check.h"
#include "SPI_Slave_Communication.h"
#include "Slave_Monitoring.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 ---------------------------------------------------------*/
ADC_HandleTypeDef hadc1;
ADC_HandleTypeDef hadc2;
DMA_HandleTypeDef hdma_adc1;
DMA_HandleTypeDef hdma_adc2;
CRC_HandleTypeDef hcrc;
FDCAN_HandleTypeDef hfdcan1;
SPI_HandleTypeDef hspi1;
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_DMA_Init(void);
static void MX_ADC1_Init(void);
static void MX_ADC2_Init(void);
static void MX_FDCAN1_Init(void);
static void MX_SPI1_Init(void);
static void MX_CRC_Init(void);
/* USER CODE BEGIN PFP */
void setAMSError(void);
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
AIRStateHandler airstates;
ErrorFlags errorflags;
AMSErrorHandle defaulterrorhandle = {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_DMA_Init();
MX_ADC1_Init();
MX_ADC2_Init();
MX_FDCAN1_Init();
MX_SPI1_Init();
MX_CRC_Init();
/* USER CODE BEGIN 2 */
airstates = init_AIR_State_Maschine(&hadc1, &hadc2, &hdma_adc1, &hdma_adc2);
initSlaves();
set_SPI_errorInfo(&defaulterrorhandle);
spi_communication_init(&hspi1, &airstates);
CAN_Init(&hfdcan1);
HAL_GPIO_WritePin(Status_LED_GPIO_Port, Status_LED_Pin, GPIO_PIN_SET);
// setAMSError();
uint32_t lastCycle = HAL_GetTick();
uint32_t cycleTime = HAL_GetTick();
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1) {
cycleTime = HAL_GetTick() - lastCycle;
lastCycle = HAL_GetTick();
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
CAN_Receive(&hfdcan1); // Run CAN Event Loop
errorflags = CheckErrorFlags(); // Check for Errors
Update_AIR_Info(&airstates);
checkSlaveTimeout(); // check for Slave Timeout
Update_AIR_State(&airstates); // Update AIR State Maschine
checkSPI(); // Handles SPI Communication*
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void) {
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
/** Configure the main internal regulator output voltage
*/
HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1);
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1;
RCC_OscInitStruct.PLL.PLLN = 8;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV8;
RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
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_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
Error_Handler();
}
}
/**
* @brief ADC1 Initialization Function
* @param None
* @retval None
*/
static void MX_ADC1_Init(void) {
/* USER CODE BEGIN ADC1_Init 0 */
/* USER CODE END ADC1_Init 0 */
ADC_MultiModeTypeDef multimode = {0};
ADC_ChannelConfTypeDef sConfig = {0};
/* USER CODE BEGIN ADC1_Init 1 */
/* USER CODE END ADC1_Init 1 */
/** Common config
*/
hadc1.Instance = ADC1;
hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV64;
hadc1.Init.Resolution = ADC_RESOLUTION_12B;
hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc1.Init.GainCompensation = 0;
hadc1.Init.ScanConvMode = ADC_SCAN_ENABLE;
hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc1.Init.LowPowerAutoWait = DISABLE;
hadc1.Init.ContinuousConvMode = DISABLE;
hadc1.Init.NbrOfConversion = 4;
hadc1.Init.DiscontinuousConvMode = DISABLE;
hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
hadc1.Init.DMAContinuousRequests = DISABLE;
hadc1.Init.Overrun = ADC_OVR_DATA_PRESERVED;
hadc1.Init.OversamplingMode = DISABLE;
if (HAL_ADC_Init(&hadc1) != HAL_OK) {
Error_Handler();
}
/** Configure the ADC multi-mode
*/
multimode.Mode = ADC_MODE_INDEPENDENT;
if (HAL_ADCEx_MultiModeConfigChannel(&hadc1, &multimode) != HAL_OK) {
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_1;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) {
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_2;
sConfig.Rank = ADC_REGULAR_RANK_2;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) {
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_3;
sConfig.Rank = ADC_REGULAR_RANK_3;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) {
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_4;
sConfig.Rank = ADC_REGULAR_RANK_4;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN ADC1_Init 2 */
/* USER CODE END ADC1_Init 2 */
}
/**
* @brief ADC2 Initialization Function
* @param None
* @retval None
*/
static void MX_ADC2_Init(void) {
/* USER CODE BEGIN ADC2_Init 0 */
/* USER CODE END ADC2_Init 0 */
ADC_ChannelConfTypeDef sConfig = {0};
/* USER CODE BEGIN ADC2_Init 1 */
/* USER CODE END ADC2_Init 1 */
/** Common config
*/
hadc2.Instance = ADC2;
hadc2.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV64;
hadc2.Init.Resolution = ADC_RESOLUTION_12B;
hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc2.Init.GainCompensation = 0;
hadc2.Init.ScanConvMode = ADC_SCAN_DISABLE;
hadc2.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc2.Init.LowPowerAutoWait = DISABLE;
hadc2.Init.ContinuousConvMode = DISABLE;
hadc2.Init.NbrOfConversion = 1;
hadc2.Init.DiscontinuousConvMode = DISABLE;
hadc2.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
hadc2.Init.DMAContinuousRequests = DISABLE;
hadc2.Init.Overrun = ADC_OVR_DATA_PRESERVED;
hadc2.Init.OversamplingMode = DISABLE;
if (HAL_ADC_Init(&hadc2) != HAL_OK) {
Error_Handler();
}
/** Configure Regular Channel
*/
sConfig.Channel = ADC_CHANNEL_17;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5;
sConfig.SingleDiff = ADC_SINGLE_ENDED;
sConfig.OffsetNumber = ADC_OFFSET_NONE;
sConfig.Offset = 0;
if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN ADC2_Init 2 */
/* USER CODE END ADC2_Init 2 */
}
/**
* @brief CRC Initialization Function
* @param None
* @retval None
*/
static void MX_CRC_Init(void) {
/* USER CODE BEGIN CRC_Init 0 */
/* USER CODE END CRC_Init 0 */
/* USER CODE BEGIN CRC_Init 1 */
/* USER CODE END CRC_Init 1 */
hcrc.Instance = CRC;
hcrc.Init.DefaultPolynomialUse = DEFAULT_POLYNOMIAL_ENABLE;
hcrc.Init.DefaultInitValueUse = DEFAULT_INIT_VALUE_ENABLE;
hcrc.Init.InputDataInversionMode = CRC_INPUTDATA_INVERSION_NONE;
hcrc.Init.OutputDataInversionMode = CRC_OUTPUTDATA_INVERSION_DISABLE;
hcrc.InputDataFormat = CRC_INPUTDATA_FORMAT_BYTES;
if (HAL_CRC_Init(&hcrc) != HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN CRC_Init 2 */
/* USER CODE END CRC_Init 2 */
}
/**
* @brief FDCAN1 Initialization Function
* @param None
* @retval None
*/
static void MX_FDCAN1_Init(void) {
/* USER CODE BEGIN FDCAN1_Init 0 */
/* USER CODE END FDCAN1_Init 0 */
/* USER CODE BEGIN FDCAN1_Init 1 */
/* USER CODE END FDCAN1_Init 1 */
hfdcan1.Instance = FDCAN1;
hfdcan1.Init.ClockDivider = FDCAN_CLOCK_DIV1;
hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC;
hfdcan1.Init.Mode = FDCAN_MODE_NORMAL;
hfdcan1.Init.AutoRetransmission = DISABLE;
hfdcan1.Init.TransmitPause = DISABLE;
hfdcan1.Init.ProtocolException = DISABLE;
hfdcan1.Init.NominalPrescaler = 2;
hfdcan1.Init.NominalSyncJumpWidth = 4;
hfdcan1.Init.NominalTimeSeg1 = 13;
hfdcan1.Init.NominalTimeSeg2 = 2;
hfdcan1.Init.DataPrescaler = 2;
hfdcan1.Init.DataSyncJumpWidth = 4;
hfdcan1.Init.DataTimeSeg1 = 13;
hfdcan1.Init.DataTimeSeg2 = 2;
hfdcan1.Init.StdFiltersNbr = 0;
hfdcan1.Init.ExtFiltersNbr = 0;
hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN FDCAN1_Init 2 */
/* USER CODE END FDCAN1_Init 2 */
}
/**
* @brief SPI1 Initialization Function
* @param None
* @retval None
*/
static void MX_SPI1_Init(void) {
/* USER CODE BEGIN SPI1_Init 0 */
/* USER CODE END SPI1_Init 0 */
/* USER CODE BEGIN SPI1_Init 1 */
/* USER CODE END SPI1_Init 1 */
/* SPI1 parameter configuration*/
hspi1.Instance = SPI1;
hspi1.Init.Mode = SPI_MODE_SLAVE;
hspi1.Init.Direction = SPI_DIRECTION_2LINES;
hspi1.Init.DataSize = SPI_DATASIZE_8BIT;
hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
hspi1.Init.NSS = SPI_NSS_SOFT;
hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
hspi1.Init.CRCPolynomial = 7;
hspi1.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
hspi1.Init.NSSPMode = SPI_NSS_PULSE_DISABLE;
if (HAL_SPI_Init(&hspi1) != HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN SPI1_Init 2 */
/* USER CODE END SPI1_Init 2 */
}
/**
* Enable DMA controller clock
*/
static void MX_DMA_Init(void) {
/* DMA controller clock enable */
__HAL_RCC_DMAMUX1_CLK_ENABLE();
__HAL_RCC_DMA1_CLK_ENABLE();
__HAL_RCC_DMA2_CLK_ENABLE();
/* DMA interrupt init */
/* DMA1_Channel2_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DMA1_Channel2_IRQn, 4, 0);
HAL_NVIC_EnableIRQ(DMA1_Channel2_IRQn);
/* DMA2_Channel1_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DMA2_Channel1_IRQn, 4, 0);
HAL_NVIC_EnableIRQ(DMA2_Channel1_IRQn);
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void) {
GPIO_InitTypeDef GPIO_InitStruct = {0};
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOC,
Slaves_Enable_Pin | BOOT0_FF_CLK_Pin | BOOT0_FF_DATA_Pin,
GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOA, Inter_STM_IRQ_Pin | Status_LED_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOB,
PreCharge_Control_Pin | AIR_Positive_Control_Pin |
AIR_negative_Control_Pin,
GPIO_PIN_RESET);
/*Configure GPIO pins : Slaves_Enable_Pin BOOT0_FF_CLK_Pin BOOT0_FF_DATA_Pin
*/
GPIO_InitStruct.Pin =
Slaves_Enable_Pin | BOOT0_FF_CLK_Pin | BOOT0_FF_DATA_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/*Configure GPIO pins : AMS_ERROR_Pin IMD_Error_Pin AMS_Error_LED_Pin
Volt_Error_CPU_Pin Positive_Side_Error_CPU_Pin Neg_Side_Error_CPU_Pin
HV_Inactive_CPU_Pin Neg_AIR_Open_CPU_Pin High_Side_Open_CPU_Pin
IMD_Error_LED_Pin */
GPIO_InitStruct.Pin = AMS_ERROR_Pin | IMD_Error_Pin | AMS_Error_LED_Pin |
Volt_Error_CPU_Pin | Positive_Side_Error_CPU_Pin |
Neg_Side_Error_CPU_Pin | HV_Inactive_CPU_Pin |
Neg_AIR_Open_CPU_Pin | High_Side_Open_CPU_Pin |
IMD_Error_LED_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/*Configure GPIO pin : Inter_STM_CS_Pin */
GPIO_InitStruct.Pin = Inter_STM_CS_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(Inter_STM_CS_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : Inter_STM_IRQ_Pin Status_LED_Pin */
GPIO_InitStruct.Pin = Inter_STM_IRQ_Pin | Status_LED_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/*Configure GPIO pins : PreCharge_Control_Pin AIR_Positive_Control_Pin
* AIR_negative_Control_Pin */
GPIO_InitStruct.Pin = PreCharge_Control_Pin | AIR_Positive_Control_Pin |
AIR_negative_Control_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}
/* USER CODE BEGIN 4 */
void AMS_Error_Handler(AMSErrorHandle errorinfo) {
while (1) {
set_SPI_errorInfo(&errorinfo);
errorinfo.errorarg[7] = 1;
setAMSError();
airstates.targetTSState = TS_ERROR;
Update_AIR_State(&airstates);
CAN_Receive(&hfdcan1);
errorflags = CheckErrorFlags();
checkSPI();
}
}
int errors = 0;
void setAMSError() {
errors++;
GPIO_InitTypeDef GPIO_InitStruct = {0};
GPIO_InitStruct.Pin = AMS_ERROR_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(AMS_ERROR_GPIO_Port, &GPIO_InitStruct);
HAL_GPIO_WritePin(AMS_ERROR_GPIO_Port, AMS_ERROR_Pin, GPIO_PIN_RESET);
}
/* 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 */
__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,507 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32g4xx_hal_msp.c
* @brief This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
extern DMA_HandleTypeDef hdma_adc1;
extern DMA_HandleTypeDef hdma_adc2;
/* 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*/
/* MemoryManagement_IRQn interrupt configuration */
HAL_NVIC_SetPriority(MemoryManagement_IRQn, 4, 0);
/* BusFault_IRQn interrupt configuration */
HAL_NVIC_SetPriority(BusFault_IRQn, 4, 0);
/* UsageFault_IRQn interrupt configuration */
HAL_NVIC_SetPriority(UsageFault_IRQn, 4, 0);
/* SVCall_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SVCall_IRQn, 4, 0);
/* DebugMonitor_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DebugMonitor_IRQn, 4, 0);
/* PendSV_IRQn interrupt configuration */
HAL_NVIC_SetPriority(PendSV_IRQn, 4, 0);
/** Disable the internal Pull-Up in Dead Battery pins of UCPD peripheral
*/
HAL_PWREx_DisableUCPDDeadBattery();
/* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */
}
static uint32_t HAL_RCC_ADC12_CLK_ENABLED=0;
/**
* @brief ADC MSP Initialization
* This function configures the hardware resources used in this example
* @param hadc: ADC handle pointer
* @retval None
*/
void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
if(hadc->Instance==ADC1)
{
/* USER CODE BEGIN ADC1_MspInit 0 */
/* USER CODE END ADC1_MspInit 0 */
/** Initializes the peripherals clocks
*/
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC12;
PeriphClkInit.Adc12ClockSelection = RCC_ADC12CLKSOURCE_SYSCLK;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
/* Peripheral clock enable */
HAL_RCC_ADC12_CLK_ENABLED++;
if(HAL_RCC_ADC12_CLK_ENABLED==1){
__HAL_RCC_ADC12_CLK_ENABLE();
}
__HAL_RCC_GPIOA_CLK_ENABLE();
/**ADC1 GPIO Configuration
PA0 ------> ADC1_IN1
PA1 ------> ADC1_IN2
PA2 ------> ADC1_IN3
PA3 ------> ADC1_IN4
*/
GPIO_InitStruct.Pin = Relay_Supply_Voltage_Pin|Pos_AIR_Current_Pin|Neg_AIR_Current_Pin|PreCharge_AIR_Current_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* ADC1 DMA Init */
/* ADC1 Init */
hdma_adc1.Instance = DMA1_Channel2;
hdma_adc1.Init.Request = DMA_REQUEST_ADC1;
hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc1.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
hdma_adc1.Init.Mode = DMA_NORMAL;
hdma_adc1.Init.Priority = DMA_PRIORITY_LOW;
if (HAL_DMA_Init(&hdma_adc1) != HAL_OK)
{
Error_Handler();
}
__HAL_LINKDMA(hadc,DMA_Handle,hdma_adc1);
/* ADC1 interrupt Init */
HAL_NVIC_SetPriority(ADC1_2_IRQn, 4, 0);
HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
/* USER CODE BEGIN ADC1_MspInit 1 */
/* USER CODE END ADC1_MspInit 1 */
}
else if(hadc->Instance==ADC2)
{
/* USER CODE BEGIN ADC2_MspInit 0 */
/* USER CODE END ADC2_MspInit 0 */
/** Initializes the peripherals clocks
*/
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC12;
PeriphClkInit.Adc12ClockSelection = RCC_ADC12CLKSOURCE_SYSCLK;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
/* Peripheral clock enable */
HAL_RCC_ADC12_CLK_ENABLED++;
if(HAL_RCC_ADC12_CLK_ENABLED==1){
__HAL_RCC_ADC12_CLK_ENABLE();
}
__HAL_RCC_GPIOA_CLK_ENABLE();
/**ADC2 GPIO Configuration
PA4 ------> ADC2_IN17
*/
GPIO_InitStruct.Pin = SC_Supply_Voltage_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(SC_Supply_Voltage_GPIO_Port, &GPIO_InitStruct);
/* ADC2 DMA Init */
/* ADC2 Init */
hdma_adc2.Instance = DMA2_Channel1;
hdma_adc2.Init.Request = DMA_REQUEST_ADC2;
hdma_adc2.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc2.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc2.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc2.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
hdma_adc2.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
hdma_adc2.Init.Mode = DMA_NORMAL;
hdma_adc2.Init.Priority = DMA_PRIORITY_LOW;
if (HAL_DMA_Init(&hdma_adc2) != HAL_OK)
{
Error_Handler();
}
__HAL_LINKDMA(hadc,DMA_Handle,hdma_adc2);
/* ADC2 interrupt Init */
HAL_NVIC_SetPriority(ADC1_2_IRQn, 4, 0);
HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
/* USER CODE BEGIN ADC2_MspInit 1 */
/* USER CODE END ADC2_MspInit 1 */
}
}
/**
* @brief ADC MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hadc: ADC handle pointer
* @retval None
*/
void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc)
{
if(hadc->Instance==ADC1)
{
/* USER CODE BEGIN ADC1_MspDeInit 0 */
/* USER CODE END ADC1_MspDeInit 0 */
/* Peripheral clock disable */
HAL_RCC_ADC12_CLK_ENABLED--;
if(HAL_RCC_ADC12_CLK_ENABLED==0){
__HAL_RCC_ADC12_CLK_DISABLE();
}
/**ADC1 GPIO Configuration
PA0 ------> ADC1_IN1
PA1 ------> ADC1_IN2
PA2 ------> ADC1_IN3
PA3 ------> ADC1_IN4
*/
HAL_GPIO_DeInit(GPIOA, Relay_Supply_Voltage_Pin|Pos_AIR_Current_Pin|Neg_AIR_Current_Pin|PreCharge_AIR_Current_Pin);
/* ADC1 DMA DeInit */
HAL_DMA_DeInit(hadc->DMA_Handle);
/* ADC1 interrupt DeInit */
/* USER CODE BEGIN ADC1:ADC1_2_IRQn disable */
/**
* Uncomment the line below to disable the "ADC1_2_IRQn" interrupt
* Be aware, disabling shared interrupt may affect other IPs
*/
/* HAL_NVIC_DisableIRQ(ADC1_2_IRQn); */
/* USER CODE END ADC1:ADC1_2_IRQn disable */
/* USER CODE BEGIN ADC1_MspDeInit 1 */
/* USER CODE END ADC1_MspDeInit 1 */
}
else if(hadc->Instance==ADC2)
{
/* USER CODE BEGIN ADC2_MspDeInit 0 */
/* USER CODE END ADC2_MspDeInit 0 */
/* Peripheral clock disable */
HAL_RCC_ADC12_CLK_ENABLED--;
if(HAL_RCC_ADC12_CLK_ENABLED==0){
__HAL_RCC_ADC12_CLK_DISABLE();
}
/**ADC2 GPIO Configuration
PA4 ------> ADC2_IN17
*/
HAL_GPIO_DeInit(SC_Supply_Voltage_GPIO_Port, SC_Supply_Voltage_Pin);
/* ADC2 DMA DeInit */
HAL_DMA_DeInit(hadc->DMA_Handle);
/* ADC2 interrupt DeInit */
/* USER CODE BEGIN ADC2:ADC1_2_IRQn disable */
/**
* Uncomment the line below to disable the "ADC1_2_IRQn" interrupt
* Be aware, disabling shared interrupt may affect other IPs
*/
/* HAL_NVIC_DisableIRQ(ADC1_2_IRQn); */
/* USER CODE END ADC2:ADC1_2_IRQn disable */
/* USER CODE BEGIN ADC2_MspDeInit 1 */
/* USER CODE END ADC2_MspDeInit 1 */
}
}
/**
* @brief CRC MSP Initialization
* This function configures the hardware resources used in this example
* @param hcrc: CRC handle pointer
* @retval None
*/
void HAL_CRC_MspInit(CRC_HandleTypeDef* hcrc)
{
if(hcrc->Instance==CRC)
{
/* USER CODE BEGIN CRC_MspInit 0 */
/* USER CODE END CRC_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_CRC_CLK_ENABLE();
/* USER CODE BEGIN CRC_MspInit 1 */
/* USER CODE END CRC_MspInit 1 */
}
}
/**
* @brief CRC MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hcrc: CRC handle pointer
* @retval None
*/
void HAL_CRC_MspDeInit(CRC_HandleTypeDef* hcrc)
{
if(hcrc->Instance==CRC)
{
/* USER CODE BEGIN CRC_MspDeInit 0 */
/* USER CODE END CRC_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_CRC_CLK_DISABLE();
/* USER CODE BEGIN CRC_MspDeInit 1 */
/* USER CODE END CRC_MspDeInit 1 */
}
}
/**
* @brief FDCAN MSP Initialization
* This function configures the hardware resources used in this example
* @param hfdcan: FDCAN handle pointer
* @retval None
*/
void HAL_FDCAN_MspInit(FDCAN_HandleTypeDef* hfdcan)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
if(hfdcan->Instance==FDCAN1)
{
/* USER CODE BEGIN FDCAN1_MspInit 0 */
/* USER CODE END FDCAN1_MspInit 0 */
/** Initializes the peripherals clocks
*/
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_FDCAN;
PeriphClkInit.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
/* Peripheral clock enable */
__HAL_RCC_FDCAN_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**FDCAN1 GPIO Configuration
PA11 ------> FDCAN1_RX
PA12 ------> FDCAN1_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_LOW;
GPIO_InitStruct.Alternate = GPIO_AF9_FDCAN1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* FDCAN1 interrupt Init */
HAL_NVIC_SetPriority(FDCAN1_IT0_IRQn, 4, 0);
HAL_NVIC_EnableIRQ(FDCAN1_IT0_IRQn);
HAL_NVIC_SetPriority(FDCAN1_IT1_IRQn, 4, 0);
HAL_NVIC_EnableIRQ(FDCAN1_IT1_IRQn);
/* USER CODE BEGIN FDCAN1_MspInit 1 */
/* USER CODE END FDCAN1_MspInit 1 */
}
}
/**
* @brief FDCAN MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hfdcan: FDCAN handle pointer
* @retval None
*/
void HAL_FDCAN_MspDeInit(FDCAN_HandleTypeDef* hfdcan)
{
if(hfdcan->Instance==FDCAN1)
{
/* USER CODE BEGIN FDCAN1_MspDeInit 0 */
/* USER CODE END FDCAN1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_FDCAN_CLK_DISABLE();
/**FDCAN1 GPIO Configuration
PA11 ------> FDCAN1_RX
PA12 ------> FDCAN1_TX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* FDCAN1 interrupt DeInit */
HAL_NVIC_DisableIRQ(FDCAN1_IT0_IRQn);
HAL_NVIC_DisableIRQ(FDCAN1_IT1_IRQn);
/* USER CODE BEGIN FDCAN1_MspDeInit 1 */
/* USER CODE END FDCAN1_MspDeInit 1 */
}
}
/**
* @brief SPI MSP Initialization
* This function configures the hardware resources used in this example
* @param hspi: SPI handle pointer
* @retval None
*/
void HAL_SPI_MspInit(SPI_HandleTypeDef* hspi)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hspi->Instance==SPI1)
{
/* USER CODE BEGIN SPI1_MspInit 0 */
/* USER CODE END SPI1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_SPI1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**SPI1 GPIO Configuration
PA5 ------> SPI1_SCK
PA6 ------> SPI1_MISO
PA7 ------> SPI1_MOSI
*/
GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF5_SPI1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* SPI1 interrupt Init */
HAL_NVIC_SetPriority(SPI1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(SPI1_IRQn);
/* USER CODE BEGIN SPI1_MspInit 1 */
/* USER CODE END SPI1_MspInit 1 */
}
}
/**
* @brief SPI MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hspi: SPI handle pointer
* @retval None
*/
void HAL_SPI_MspDeInit(SPI_HandleTypeDef* hspi)
{
if(hspi->Instance==SPI1)
{
/* USER CODE BEGIN SPI1_MspDeInit 0 */
/* USER CODE END SPI1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_SPI1_CLK_DISABLE();
/**SPI1 GPIO Configuration
PA5 ------> SPI1_SCK
PA6 ------> SPI1_MISO
PA7 ------> SPI1_MOSI
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7);
/* SPI1 interrupt DeInit */
HAL_NVIC_DisableIRQ(SPI1_IRQn);
/* USER CODE BEGIN SPI1_MspDeInit 1 */
/* USER CODE END SPI1_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

301
Core/Src/stm32g4xx_it.c Normal file
View File

@ -0,0 +1,301 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32g4xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2022 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32g4xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "CAN_Communication.h"
/* 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 --------------------------------------------------------*/
extern DMA_HandleTypeDef hdma_adc1;
extern DMA_HandleTypeDef hdma_adc2;
extern ADC_HandleTypeDef hadc1;
extern ADC_HandleTypeDef hadc2;
extern FDCAN_HandleTypeDef hfdcan1;
extern SPI_HandleTypeDef hspi1;
/* USER CODE BEGIN EV */
extern uint8_t framebufferwritepointer;
extern uint8_t framebufferreadpointer;
/* USER CODE END EV */
/******************************************************************************/
/* Cortex-M4 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 */
HAL_GPIO_WritePin(Status_LED_GPIO_Port, Status_LED_Pin, GPIO_PIN_RESET);
/* USER CODE END W1_HardFault_IRQn 0 */
}
}
/**
* @brief This function handles Memory management fault.
*/
void MemManage_Handler(void)
{
/* USER CODE BEGIN MemoryManagement_IRQn 0 */
/* USER CODE END MemoryManagement_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
/* USER CODE END W1_MemoryManagement_IRQn 0 */
}
}
/**
* @brief This function handles Prefetch fault, memory access fault.
*/
void BusFault_Handler(void)
{
/* USER CODE BEGIN BusFault_IRQn 0 */
/* USER CODE END BusFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_BusFault_IRQn 0 */
/* USER CODE END W1_BusFault_IRQn 0 */
}
}
/**
* @brief This function handles Undefined instruction or illegal state.
*/
void UsageFault_Handler(void)
{
/* USER CODE BEGIN UsageFault_IRQn 0 */
/* USER CODE END UsageFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_UsageFault_IRQn 0 */
/* USER CODE END W1_UsageFault_IRQn 0 */
}
}
/**
* @brief This function handles System service call via SWI instruction.
*/
void SVC_Handler(void)
{
/* USER CODE BEGIN SVCall_IRQn 0 */
/* USER CODE END SVCall_IRQn 0 */
/* USER CODE BEGIN SVCall_IRQn 1 */
/* USER CODE END SVCall_IRQn 1 */
}
/**
* @brief This function handles Debug monitor.
*/
void DebugMon_Handler(void)
{
/* USER CODE BEGIN DebugMonitor_IRQn 0 */
/* USER CODE END DebugMonitor_IRQn 0 */
/* USER CODE BEGIN DebugMonitor_IRQn 1 */
/* USER CODE END DebugMonitor_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 */
}
/******************************************************************************/
/* STM32G4xx 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_stm32g4xx.s). */
/******************************************************************************/
/**
* @brief This function handles DMA1 channel2 global interrupt.
*/
void DMA1_Channel2_IRQHandler(void)
{
/* USER CODE BEGIN DMA1_Channel2_IRQn 0 */
/* USER CODE END DMA1_Channel2_IRQn 0 */
HAL_DMA_IRQHandler(&hdma_adc1);
/* USER CODE BEGIN DMA1_Channel2_IRQn 1 */
/* USER CODE END DMA1_Channel2_IRQn 1 */
}
/**
* @brief This function handles ADC1 and ADC2 global interrupt.
*/
void ADC1_2_IRQHandler(void)
{
/* USER CODE BEGIN ADC1_2_IRQn 0 */
/* USER CODE END ADC1_2_IRQn 0 */
HAL_ADC_IRQHandler(&hadc1);
HAL_ADC_IRQHandler(&hadc2);
/* USER CODE BEGIN ADC1_2_IRQn 1 */
/* USER CODE END ADC1_2_IRQn 1 */
}
/**
* @brief This function handles FDCAN1 interrupt 0.
*/
void FDCAN1_IT0_IRQHandler(void)
{
/* USER CODE BEGIN FDCAN1_IT0_IRQn 0 */
/* USER CODE END FDCAN1_IT0_IRQn 0 */
HAL_FDCAN_IRQHandler(&hfdcan1);
/* USER CODE BEGIN FDCAN1_IT0_IRQn 1 */
/* USER CODE END FDCAN1_IT0_IRQn 1 */
}
/**
* @brief This function handles FDCAN1 interrupt 1.
*/
void FDCAN1_IT1_IRQHandler(void)
{
/* USER CODE BEGIN FDCAN1_IT1_IRQn 0 */
/* USER CODE END FDCAN1_IT1_IRQn 0 */
HAL_FDCAN_IRQHandler(&hfdcan1);
/* USER CODE BEGIN FDCAN1_IT1_IRQn 1 */
/* USER CODE END FDCAN1_IT1_IRQn 1 */
}
/**
* @brief This function handles SPI1 global interrupt.
*/
void SPI1_IRQHandler(void)
{
/* USER CODE BEGIN SPI1_IRQn 0 */
/* USER CODE END SPI1_IRQn 0 */
HAL_SPI_IRQHandler(&hspi1);
/* USER CODE BEGIN SPI1_IRQn 1 */
/* USER CODE END SPI1_IRQn 1 */
}
/**
* @brief This function handles DMA2 channel1 global interrupt.
*/
void DMA2_Channel1_IRQHandler(void)
{
/* USER CODE BEGIN DMA2_Channel1_IRQn 0 */
/* USER CODE END DMA2_Channel1_IRQn 0 */
HAL_DMA_IRQHandler(&hdma_adc2);
/* USER CODE BEGIN DMA2_Channel1_IRQn 1 */
/* USER CODE END DMA2_Channel1_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

156
Core/Src/syscalls.c Normal file
View File

@ -0,0 +1,156 @@
/**
******************************************************************************
* @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
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* 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)
{
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)
{
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
*ptr++ = __io_getchar();
}
return len;
}
__attribute__((weak)) int _write(int file, char *ptr, int len)
{
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
__io_putchar(*ptr++);
}
return len;
}
int _close(int file)
{
return -1;
}
int _fstat(int file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
int _isatty(int file)
{
return 1;
}
int _lseek(int file, int ptr, int dir)
{
return 0;
}
int _open(char *path, int flags, ...)
{
/* Pretend like we always fail */
return -1;
}
int _wait(int *status)
{
errno = ECHILD;
return -1;
}
int _unlink(char *name)
{
errno = ENOENT;
return -1;
}
int _times(struct tms *buf)
{
return -1;
}
int _stat(char *file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
int _link(char *old, char *new)
{
errno = EMLINK;
return -1;
}
int _fork(void)
{
errno = EAGAIN;
return -1;
}
int _execve(char *name, char **argv, char **env)
{
errno = ENOMEM;
return -1;
}

80
Core/Src/sysmem.c Normal file
View File

@ -0,0 +1,80 @@
/**
******************************************************************************
* @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
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* 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;
}

287
Core/Src/system_stm32g4xx.c Normal file
View File

@ -0,0 +1,287 @@
/**
******************************************************************************
* @file system_stm32g4xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File
*
* 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_stm32g4xx.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.
*
* After each device reset the HSI (16 MHz) is used as system clock source.
* Then SystemInit() function is called, in "startup_stm32g4xx.s" file, to
* configure the system clock before to branch to main program.
*
* This file configures the system clock as follows:
*=============================================================================
*-----------------------------------------------------------------------------
* System Clock source | HSI
*-----------------------------------------------------------------------------
* SYSCLK(Hz) | 16000000
*-----------------------------------------------------------------------------
* HCLK(Hz) | 16000000
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB1 Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 1
*-----------------------------------------------------------------------------
* PLL_M | 1
*-----------------------------------------------------------------------------
* PLL_N | 16
*-----------------------------------------------------------------------------
* PLL_P | 7
*-----------------------------------------------------------------------------
* PLL_Q | 2
*-----------------------------------------------------------------------------
* PLL_R | 2
*-----------------------------------------------------------------------------
* Require 48MHz for RNG | Disabled
*-----------------------------------------------------------------------------
*=============================================================================
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2019 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32g4xx_system
* @{
*/
/** @addtogroup STM32G4xx_System_Private_Includes
* @{
*/
#include "stm32g4xx.h"
#if !defined (HSE_VALUE)
#define HSE_VALUE 24000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @}
*/
/** @addtogroup STM32G4xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32G4xx_System_Private_Defines
* @{
*/
/************************* Miscellaneous Configuration ************************/
/* Note: Following vector table addresses must be defined in line with linker
configuration. */
/*!< Uncomment the following line if you need to relocate the vector table
anywhere in Flash or Sram, else the vector table is kept at the automatic
remap of boot address selected */
/* #define USER_VECT_TAB_ADDRESS */
#if defined(USER_VECT_TAB_ADDRESS)
/*!< Uncomment the following line if you need to relocate your vector Table
in Sram else user remap will be done in Flash. */
/* #define VECT_TAB_SRAM */
#if defined(VECT_TAB_SRAM)
#define VECT_TAB_BASE_ADDRESS SRAM_BASE /*!< Vector Table base address field.
This value must be a multiple of 0x200. */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
#else
#define VECT_TAB_BASE_ADDRESS FLASH_BASE /*!< Vector Table base address field.
This value must be a multiple of 0x200. */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
#endif /* VECT_TAB_SRAM */
#endif /* USER_VECT_TAB_ADDRESS */
/******************************************************************************/
/**
* @}
*/
/** @addtogroup STM32G4xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32G4xx_System_Private_Variables
* @{
*/
/* The SystemCoreClock 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 = HSI_VALUE;
const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U};
const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U};
/**
* @}
*/
/** @addtogroup STM32G4xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32G4xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system.
* @param None
* @retval None
*/
void SystemInit(void)
{
/* FPU settings ------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << (10*2))|(3UL << (11*2))); /* set CP10 and CP11 Full Access */
#endif
/* Configure the Vector Table location add offset address ------------------*/
#if defined(USER_VECT_TAB_ADDRESS)
SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
#endif /* USER_VECT_TAB_ADDRESS */
}
/**
* @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.
*
* (**) HSI_VALUE is a constant defined in stm32g4xx_hal.h file (default value
* 16 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (***) HSE_VALUE is a constant defined in stm32g4xx_hal.h file (default value
* 24 MHz), user has to ensure that HSE_VALUE is same as the real
* frequency of the crystal used. Otherwise, this function may
* have wrong result.
*
* - 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, pllvco, pllr, pllsource, pllm;
/* Get SYSCLK source -------------------------------------------------------*/
switch (RCC->CFGR & RCC_CFGR_SWS)
{
case 0x04: /* HSI used as system clock source */
SystemCoreClock = HSI_VALUE;
break;
case 0x08: /* HSE used as system clock source */
SystemCoreClock = HSE_VALUE;
break;
case 0x0C: /* PLL used as system clock source */
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
SYSCLK = PLL_VCO / PLLR
*/
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4) + 1U ;
if (pllsource == 0x02UL) /* HSI used as PLL clock source */
{
pllvco = (HSI_VALUE / pllm);
}
else /* HSE used as PLL clock source */
{
pllvco = (HSE_VALUE / pllm);
}
pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8);
pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25) + 1U) * 2U;
SystemCoreClock = pllvco/pllr;
break;
default:
break;
}
/* Compute HCLK clock frequency --------------------------------------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,502 @@
/**
******************************************************************************
* @file startup_stm32g441xx.s
* @author MCD Application Team
* @brief STM32G441xx devices vector table 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,
* - Configure the clock system
* - Branches to main in the C library (which eventually
* calls main()).
* After Reset the Cortex-M4 processor is in Thread mode,
* priority is Privileged, and the Stack is set to Main.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2019 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
.syntax unified
.cpu cortex-m4
.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
.equ BootRAM, 0xF1E0F85F
/**
* @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 */
/* 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 the clock system intitialization function.*/
bl SystemInit
/* Call static constructors */
bl __libc_init_array
/* Call the application's entry point.*/
bl main
LoopForever:
b LoopForever
.size Reset_Handler, .-Reset_Handler
/**
* @brief This is the code that gets called when the processor receives an
* unexpected interrupt. This simply enters an infinite loop, preserving
* the system state for examination by a debugger.
*
* @param None
* @retval : None
*/
.section .text.Default_Handler,"ax",%progbits
Default_Handler:
Infinite_Loop:
b Infinite_Loop
.size Default_Handler, .-Default_Handler
/******************************************************************************
*
* The minimal vector table for a Cortex-M4. 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 MemManage_Handler
.word BusFault_Handler
.word UsageFault_Handler
.word 0
.word 0
.word 0
.word 0
.word SVC_Handler
.word DebugMon_Handler
.word 0
.word PendSV_Handler
.word SysTick_Handler
.word WWDG_IRQHandler
.word PVD_PVM_IRQHandler
.word RTC_TAMP_LSECSS_IRQHandler
.word RTC_WKUP_IRQHandler
.word FLASH_IRQHandler
.word RCC_IRQHandler
.word EXTI0_IRQHandler
.word EXTI1_IRQHandler
.word EXTI2_IRQHandler
.word EXTI3_IRQHandler
.word EXTI4_IRQHandler
.word DMA1_Channel1_IRQHandler
.word DMA1_Channel2_IRQHandler
.word DMA1_Channel3_IRQHandler
.word DMA1_Channel4_IRQHandler
.word DMA1_Channel5_IRQHandler
.word DMA1_Channel6_IRQHandler
.word 0
.word ADC1_2_IRQHandler
.word USB_HP_IRQHandler
.word USB_LP_IRQHandler
.word FDCAN1_IT0_IRQHandler
.word FDCAN1_IT1_IRQHandler
.word EXTI9_5_IRQHandler
.word TIM1_BRK_TIM15_IRQHandler
.word TIM1_UP_TIM16_IRQHandler
.word TIM1_TRG_COM_TIM17_IRQHandler
.word TIM1_CC_IRQHandler
.word TIM2_IRQHandler
.word TIM3_IRQHandler
.word TIM4_IRQHandler
.word I2C1_EV_IRQHandler
.word I2C1_ER_IRQHandler
.word I2C2_EV_IRQHandler
.word I2C2_ER_IRQHandler
.word SPI1_IRQHandler
.word SPI2_IRQHandler
.word USART1_IRQHandler
.word USART2_IRQHandler
.word USART3_IRQHandler
.word EXTI15_10_IRQHandler
.word RTC_Alarm_IRQHandler
.word USBWakeUp_IRQHandler
.word TIM8_BRK_IRQHandler
.word TIM8_UP_IRQHandler
.word TIM8_TRG_COM_IRQHandler
.word TIM8_CC_IRQHandler
.word 0
.word 0
.word LPTIM1_IRQHandler
.word 0
.word SPI3_IRQHandler
.word UART4_IRQHandler
.word 0
.word TIM6_DAC_IRQHandler
.word TIM7_IRQHandler
.word DMA2_Channel1_IRQHandler
.word DMA2_Channel2_IRQHandler
.word DMA2_Channel3_IRQHandler
.word DMA2_Channel4_IRQHandler
.word DMA2_Channel5_IRQHandler
.word 0
.word 0
.word UCPD1_IRQHandler
.word COMP1_2_3_IRQHandler
.word COMP4_IRQHandler
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word CRS_IRQHandler
.word SAI1_IRQHandler
.word 0
.word 0
.word 0
.word 0
.word FPU_IRQHandler
.word 0
.word 0
.word 0
.word AES_IRQHandler
.word 0
.word 0
.word 0
.word 0
.word RNG_IRQHandler
.word LPUART1_IRQHandler
.word I2C3_EV_IRQHandler
.word I2C3_ER_IRQHandler
.word DMAMUX_OVR_IRQHandler
.word 0
.word 0
.word DMA2_Channel6_IRQHandler
.word 0
.word 0
.word CORDIC_IRQHandler
.word FMAC_IRQHandler
/*******************************************************************************
*
* 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 MemManage_Handler
.thumb_set MemManage_Handler,Default_Handler
.weak BusFault_Handler
.thumb_set BusFault_Handler,Default_Handler
.weak UsageFault_Handler
.thumb_set UsageFault_Handler,Default_Handler
.weak SVC_Handler
.thumb_set SVC_Handler,Default_Handler
.weak DebugMon_Handler
.thumb_set DebugMon_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_PVM_IRQHandler
.thumb_set PVD_PVM_IRQHandler,Default_Handler
.weak RTC_TAMP_LSECSS_IRQHandler
.thumb_set RTC_TAMP_LSECSS_IRQHandler,Default_Handler
.weak RTC_WKUP_IRQHandler
.thumb_set RTC_WKUP_IRQHandler,Default_Handler
.weak FLASH_IRQHandler
.thumb_set FLASH_IRQHandler,Default_Handler
.weak RCC_IRQHandler
.thumb_set RCC_IRQHandler,Default_Handler
.weak EXTI0_IRQHandler
.thumb_set EXTI0_IRQHandler,Default_Handler
.weak EXTI1_IRQHandler
.thumb_set EXTI1_IRQHandler,Default_Handler
.weak EXTI2_IRQHandler
.thumb_set EXTI2_IRQHandler,Default_Handler
.weak EXTI3_IRQHandler
.thumb_set EXTI3_IRQHandler,Default_Handler
.weak EXTI4_IRQHandler
.thumb_set EXTI4_IRQHandler,Default_Handler
.weak DMA1_Channel1_IRQHandler
.thumb_set DMA1_Channel1_IRQHandler,Default_Handler
.weak DMA1_Channel2_IRQHandler
.thumb_set DMA1_Channel2_IRQHandler,Default_Handler
.weak DMA1_Channel3_IRQHandler
.thumb_set DMA1_Channel3_IRQHandler,Default_Handler
.weak DMA1_Channel4_IRQHandler
.thumb_set DMA1_Channel4_IRQHandler,Default_Handler
.weak DMA1_Channel5_IRQHandler
.thumb_set DMA1_Channel5_IRQHandler,Default_Handler
.weak DMA1_Channel6_IRQHandler
.thumb_set DMA1_Channel6_IRQHandler,Default_Handler
.weak ADC1_2_IRQHandler
.thumb_set ADC1_2_IRQHandler,Default_Handler
.weak USB_HP_IRQHandler
.thumb_set USB_HP_IRQHandler,Default_Handler
.weak USB_LP_IRQHandler
.thumb_set USB_LP_IRQHandler,Default_Handler
.weak FDCAN1_IT0_IRQHandler
.thumb_set FDCAN1_IT0_IRQHandler,Default_Handler
.weak FDCAN1_IT1_IRQHandler
.thumb_set FDCAN1_IT1_IRQHandler,Default_Handler
.weak EXTI9_5_IRQHandler
.thumb_set EXTI9_5_IRQHandler,Default_Handler
.weak TIM1_BRK_TIM15_IRQHandler
.thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
.weak TIM1_UP_TIM16_IRQHandler
.thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
.weak TIM1_TRG_COM_TIM17_IRQHandler
.thumb_set TIM1_TRG_COM_TIM17_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 TIM4_IRQHandler
.thumb_set TIM4_IRQHandler,Default_Handler
.weak I2C1_EV_IRQHandler
.thumb_set I2C1_EV_IRQHandler,Default_Handler
.weak I2C1_ER_IRQHandler
.thumb_set I2C1_ER_IRQHandler,Default_Handler
.weak I2C2_EV_IRQHandler
.thumb_set I2C2_EV_IRQHandler,Default_Handler
.weak I2C2_ER_IRQHandler
.thumb_set I2C2_ER_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 USART3_IRQHandler
.thumb_set USART3_IRQHandler,Default_Handler
.weak EXTI15_10_IRQHandler
.thumb_set EXTI15_10_IRQHandler,Default_Handler
.weak RTC_Alarm_IRQHandler
.thumb_set RTC_Alarm_IRQHandler,Default_Handler
.weak USBWakeUp_IRQHandler
.thumb_set USBWakeUp_IRQHandler,Default_Handler
.weak TIM8_BRK_IRQHandler
.thumb_set TIM8_BRK_IRQHandler,Default_Handler
.weak TIM8_UP_IRQHandler
.thumb_set TIM8_UP_IRQHandler,Default_Handler
.weak TIM8_TRG_COM_IRQHandler
.thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
.weak TIM8_CC_IRQHandler
.thumb_set TIM8_CC_IRQHandler,Default_Handler
.weak LPTIM1_IRQHandler
.thumb_set LPTIM1_IRQHandler,Default_Handler
.weak SPI3_IRQHandler
.thumb_set SPI3_IRQHandler,Default_Handler
.weak UART4_IRQHandler
.thumb_set UART4_IRQHandler,Default_Handler
.weak TIM6_DAC_IRQHandler
.thumb_set TIM6_DAC_IRQHandler,Default_Handler
.weak TIM7_IRQHandler
.thumb_set TIM7_IRQHandler,Default_Handler
.weak DMA2_Channel1_IRQHandler
.thumb_set DMA2_Channel1_IRQHandler,Default_Handler
.weak DMA2_Channel2_IRQHandler
.thumb_set DMA2_Channel2_IRQHandler,Default_Handler
.weak DMA2_Channel3_IRQHandler
.thumb_set DMA2_Channel3_IRQHandler,Default_Handler
.weak DMA2_Channel4_IRQHandler
.thumb_set DMA2_Channel4_IRQHandler,Default_Handler
.weak DMA2_Channel5_IRQHandler
.thumb_set DMA2_Channel5_IRQHandler,Default_Handler
.weak UCPD1_IRQHandler
.thumb_set UCPD1_IRQHandler,Default_Handler
.weak COMP1_2_3_IRQHandler
.thumb_set COMP1_2_3_IRQHandler,Default_Handler
.weak COMP4_IRQHandler
.thumb_set COMP4_IRQHandler,Default_Handler
.weak CRS_IRQHandler
.thumb_set CRS_IRQHandler,Default_Handler
.weak SAI1_IRQHandler
.thumb_set SAI1_IRQHandler,Default_Handler
.weak FPU_IRQHandler
.thumb_set FPU_IRQHandler,Default_Handler
.weak AES_IRQHandler
.thumb_set AES_IRQHandler,Default_Handler
.weak RNG_IRQHandler
.thumb_set RNG_IRQHandler,Default_Handler
.weak LPUART1_IRQHandler
.thumb_set LPUART1_IRQHandler,Default_Handler
.weak I2C3_EV_IRQHandler
.thumb_set I2C3_EV_IRQHandler,Default_Handler
.weak I2C3_ER_IRQHandler
.thumb_set I2C3_ER_IRQHandler,Default_Handler
.weak DMAMUX_OVR_IRQHandler
.thumb_set DMAMUX_OVR_IRQHandler,Default_Handler
.weak DMA2_Channel6_IRQHandler
.thumb_set DMA2_Channel6_IRQHandler,Default_Handler
.weak CORDIC_IRQHandler
.thumb_set CORDIC_IRQHandler,Default_Handler
.weak FMAC_IRQHandler
.thumb_set FMAC_IRQHandler,Default_Handler
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/