merged the MVBMS repos, prob fucked both

This commit is contained in:
2025-02-22 15:14:28 +01:00
parent 2b73443e07
commit abb9851b60
1137 changed files with 875974 additions and 28 deletions

View File

@ -0,0 +1,106 @@
/*
* ADBMS_Abstraction.h
*
* Created on: 14.07.2022
* Author: max
*/
#ifndef INC_ADBMS_ABSTRACTION_H_
#define INC_ADBMS_ABSTRACTION_H_
#include "ADBMS_CMD_MAKROS.h"
#include "ADBMS_LL_Driver.h"
#include "main.h"
#define MAXIMUM_CELL_VOLTAGES 16
#define MAXIMUM_AUX_VOLTAGES 10
#define MAXIMUM_GPIO 10
//see table 103 in datasheet (page 71)
#define DEFAULT_UV 417 //VUV * 16 * 150 uV + 1.5 V Default Setting 2.5V
#define DEFAULT_OV 1125 //VOV * 16 * 150 uV + 1.5 V Default Setting 4.2V
#define mV_from_ADBMS6830(x) (((((int16_t) (x))) * 0.150) + 1500)
struct ADBMS6830_Internal_Status {
uint16 CS_FLT : 16; //ADC fault - mismatch between S- and C-ADC
uint16 : 3;
uint16 CCTS : 13; //Conversion counter
uint16 VA_OV : 1; //5V analog supply overvoltage
uint16 VA_UV : 1; //5V analog supply undervoltage
uint16 VD_OV : 1; //3V digital supply overvoltage
uint16 VD_UV : 1; //3V digital supply undervoltage
uint16 CED : 1; //C-ADC single trim error (correctable)
uint16 CMED : 1; //C-ADC multiple trim error (uncorrectable)
uint16 SED : 1; //S-ADC single trim error (correctable)
uint16 SMED : 1; //S-ADC multiple trim error (uncorrectable)
uint16 VDEL : 1; //Latent supply voltage error
uint16 VDE : 1; //Supply voltage error
uint16 COMPARE : 1; //Comparasion between S- and C-ADC active
uint16 SPIFLT : 1; //SPI fault
uint16 SLEEP : 1; //Sleep mode previously entered
uint16 THSD : 1; //Thermal shutdown
uint16 TMODCHK : 1; //Test mode check
uint16 OSCCHK : 1; //Oscillator check
};
typedef struct {
int16_t cellVoltages[MAXIMUM_CELL_VOLTAGES];
float auxVoltages[MAXIMUM_AUX_VOLTAGES];
struct ADBMS6830_Internal_Status status;
uint16 internalDieTemp;
uint16 analogSupplyVoltage;
uint16 digitalSupplyVoltage;
uint16 sumOfCellMeasurements;
uint16 refVoltage;
uint16 GPIO_Values[MAXIMUM_GPIO];
uint32 overVoltage;
uint32 underVoltage;
} Cell_Module;
uint8 amsReset();
uint8 initAMS(SPI_HandleTypeDef* hspi, uint8 numofcells, uint8 numofaux);
uint8 amsWakeUp();
uint8 amsCellMeasurement(Cell_Module* module);
uint8 amsConfigCellMeasurement(uint8 numberofChannels);
uint8 amsAuxAndStatusMeasurement(Cell_Module* module);
uint8 amsConfigAuxMeasurement(uint16 Channels);
uint8 amsConfigGPIO(uint16 gpios);
uint8 amsSetGPIO(uint16 gpios);
uint8 readGPIO(Cell_Module* module);
uint8 amsConfigBalancing(uint32 Channels, uint8 dutyCycle);
uint8 amsStartBalancing(uint8 dutyCycle);
uint8 amsStopBalancing();
uint8 amsSelfTest();
uint8 amsConfigOverUnderVoltage(uint16 overVoltage, uint16 underVoltage);
uint8 amsCheckUnderOverVoltage(Cell_Module* module);
uint8 amsConfigOverVoltage(uint16 overVoltage);
uint8 amscheckOpenCellWire(Cell_Module* module);
uint8 amsClearStatus();
uint8 amsClearAux();
uint8 amsClearCells();
uint8 amsSendWarning();
uint8 amsSendError();
uint8 amsClearWarning();
uint8 amsClearError();
uint8 amsReadCellVoltages(Cell_Module* module);
#endif /* INC_ADBMS_ABSTRACTION_H_ */

View File

@ -0,0 +1,171 @@
/*
* ADBMS_CMD_MAKROS.h
*
* Created on: 14.07.2022
* Author: max
*/
#ifndef INC_ADBMS_CMD_MAKROS_H_
#define INC_ADBMS_CMD_MAKROS_H_
#include <stdint.h>
#define WRCFGA 0x0001 // Write Configuration Register Group A
#define RDCFGA 0x0002 // Read Configuration Register Group A
#define WRCFGB 0x0024 // Write Configuration Register Group B
#define RDCFGB 0x0026 // Read Configuration Register Group B
#define WRPWMA 0x0020 // Write PWM Register Group A
#define RDPWMA 0x0022 // Read PWM Register Group A
#define WRPWMB 0x0021 // Write PWM Register Group B
#define RDPWMB 0x0023 // Read PWM Register Group B
#define RDCVA 0x0004 // Read Cell Voltage Register Group A
#define RDCVB 0x0006 // Read Cell Voltage Register Group B
#define RDCVC 0x0008 // Read Cell Voltage Register Group C
#define RDCVD 0x000A // Read Cell Voltage Register Group D
#define RDCVE 0x0009 // Read Cell Voltage Register Group E
#define RDCVF 0x000B // Read Cell Voltage Register Group F
#define RDCVALL 0x000C // Read All Cell Voltage Register Groups
#define RDACA 0x0044 // Read averaged Cell Voltage Register Group A
#define RDACB 0x0046 // Read averaged Cell Voltage Register Group B
#define RDACC 0x0048 // Read averaged Cell Voltage Register Group C
#define RDACD 0x004A // Read averaged Cell Voltage Register Group D
#define RDACE 0x0049 // Read averaged Cell Voltage Register Group E
#define RDACF 0x004B // Read averaged Cell Voltage Register Group F
#define RDACALL 0x004C // Read averaged All Cell Voltage Register Groups
#define RDAUXA 0x0019 // Read Auxilliary Register Group A
#define RDAUXB 0x001A // Read Auxilliary Register Group B
#define RDAUXC 0x001B // Read Auxilliary Register Group C
#define RDAUXD 0x001F // Read Auxilliary Register Group D
#define RDAUXALL 0x0035 // Read All Auxilliary and Status Register Groups
#define RDSTATA 0x0030 // Read Status Register Group A
#define RDSTATB 0x0031 // Read Status Register Group B
#define RDSTATC 0x0032 // Read Status Register Group C
#define RDSTATD 0x0033 // Read Status Register Group D
#define RDSTATE 0x0034 // Read Status Register Group E
#define ADCV 0x0260 // Start Cell Voltage Conversion with C-ADC
#define ADCV_OW_0 (1u << 0)
#define ADCV_OW_1 (1u << 1)
#define ADCV_RSTF (1u << 2)
#define ADCV_DCP (1u << 4)
#define ADCV_CONT (1u << 7) // Continuous Mode
#define ADCV_RD (1u << 8) // Redundancy Mode
#define ADSV 0x0168 // Start Cell Voltage Conversion with S-ADC
#define ADSV_OW_0 (1u << 0)
#define ADSV_OW_1 (1u << 1)
#define ADSV_DCP (1u << 4)
#define ADSV_CONT (1u << 7) // Continuous Mode
#define ADAX 0x0410 // Start GPIOs and Vref2 Conversion
#define ADAX_CONV_ALL 0x0000 // Convert all GPIOs, VREF2, VD, VA, ITEMP
#define ADAX_OW (1u << 8)
#define CLRCELL 0x0711 // Clear Cell Voltage Register Groups
#define CLRAUX 0x0712 // Clear Auxiliary Register Groups
#define CLOVUV 0x0715 // Clear Overvoltage and Undervoltage Flags
#define CLRFLAG 0x0717 // Clear all Flags
#define PLADC 0x0718 // Poll ADC Conversion Status
#define PLAUX 0x071E // Poll AUX Conversion Status
#define SRST 0x0027 //Soft reset
#define DIAGN 0x0715 // Diagnos MUX and Poll Status
#define WRCOMM 0x0721 // Write COMM Register Group
#define RDCOMM 0x0722 // Read COMM Register Group
#define STCOMM 0x0723 // Start I2C/SPI Communication
#define MUTE 0x0028 // Mute Discharge
#define UNMUTE 0x0029 // Unmute Discharge
/* GPIO Selection for ADC Converion
* 000: GPIO1 to 5, 2nd Reference, GPIO 6 to 9
* 001: GPIO1 and GPIO6
* 010 GPIO2 and GPIO7
* 011 GPIO3 and GPIO8
* 100 GPIO4 and GPIO9
* 101 GPIO5
* 110 2nd Reference
*/
#define CHG000 (0x00)
#define CHG001 (0x01)
#define CHG010 (0x02)
#define CHG011 (0x03)
#define CHG100 (0x04)
#define CHG101 (0x05)
#define CHG110 (0x06)
/* Status Group Selection
* 000: SC,ITMP,VA,VD
* 001: SC
* 010: ITMP
* 011: VA
* 100: VD
*/
#define CHST000 (0x00)
#define CHST001 (0x01)
#define CHST010 (0x02)
#define CHST011 (0x03)
#define CHST100 (0x04)
#define PEC_FIELD_SIZE 2
#define CFG_GROUP_A_SIZE 6
#define CFG_GROUP_B_SIZE 6
#define PWM_GROUP_A_SIZE 6
#define PWM_GROUP_B_SIZE 2
#define CV_GROUP_A_SIZE 6
#define CV_GROUP_B_SIZE 6
#define CV_GROUP_C_SIZE 6
#define CV_GROUP_D_SIZE 6
#define CV_GROUP_E_SIZE 6
#define CV_GROUP_F_SIZE 6
#define AUX_GROUP_A_SIZE 6
#define AUX_GROUP_B_SIZE 6
#define AUX_GROUP_C_SIZE 6
#define AUX_GROUP_D_SIZE 6
#define STATUS_GROUP_A_SIZE 6
#define STATUS_GROUP_B_SIZE 6
#define STATUS_GROUP_C_SIZE 6
#define STATUS_GROUP_D_SIZE 6
#define STATUS_GROUP_E_SIZE 6
#define COMM_GROUP_SIZE 6
#define S_CONTROL_GROUP_SIZE 6
#define PWM_GROUP_SIZE 6
#define PWM_S_CONTROL_GROUP_B_SIZE 6
#define CFG_GROUP_A_ID 1
#define CFG_GROUP_B_ID 2
#define CV_GROUP_A_ID 3
#define CV_GROUP_B_ID 4
#define CV_GROUP_C_ID 5
#define CV_GROUP_D_ID 6
#define CV_GROUP_E_ID 7
#define CV_GROUP_F_ID 8
#define AUX_GROUP_A_ID 9
#define AUX_GROUP_B_ID 10
#define AUX_GROUP_C_ID 11
#define AUX_GROUP_D_ID 12
#define STATUS_GROUP_A_ID 13
#define STATUS_GROUP_B_ID 14
#define COMM_GROUP_ID 15
#define S_CONTROL_GROUP_ID 16
#define PWM_GROUP_ID 17
#define PWM_S_CONTROL_GROUP_B_ID 18
#endif /* INC_ADBMS_CMD_MAKROS_H_ */

View File

@ -0,0 +1,44 @@
/*
* ADBMS_LL_Driver.h
*
* Created on: 05.06.2022
* Author: max
*/
#ifndef ADBMS_LL_DRIVER_H_
#define ADBMS_LL_DRIVER_H_
#define TARGET_STM32
#include "main.h"
#ifdef TARGET_STM32
typedef uint8_t uint8;
typedef uint16_t uint16;
typedef uint32_t uint32;
#endif
uint8 adbmsDriverInit(SPI_HandleTypeDef* hspi);
uint8 calculateCommandPEC(uint8* data, uint8 datalen);
uint16 updateCommandPEC(uint16 currentPEC, uint8 din);
uint8 checkCommandPEC(uint8* data, uint8 datalen);
uint8 calculateDataPEC(uint8* data, uint8 datalen);
uint16 updateDataPEC(uint16 currentPEC, uint8 din);
uint8 checkDataPEC(uint8* data, uint8 datalen);
[[gnu::access(read_only, 2, 3)]] uint8 writeCMD(uint16 command, const uint8* args, uint8 arglen);
[[gnu::access(write_only, 2, 3)]] uint8 readCMD(uint16 command, uint8* buffer, uint8 buflen);
uint8 pollCMD(uint16 command);
void mcuAdbmsCSLow();
void mcuAdbmsCSHigh();
uint8 mcuSPITransmit(uint8* buffer, uint8 buffersize);
uint8 mcuSPIReceive(uint8* buffer, uint8 buffersize);
uint8 mcuSPITransmitReceive(uint8* rxbuffer, uint8* txbuffer, uint8 buffersize);
uint8 wakeUpCmd();
void mcuDelay(uint16 delay);
#endif /* ADBMS_LL_DRIVER_H_ */

View File

@ -0,0 +1,47 @@
/*
* AMS_HighLevel.h
*
* Created on: 20.07.2022
* Author: max
*/
#ifndef INC_AMS_HIGHLEVEL_H_
#define INC_AMS_HIGHLEVEL_H_
#include "ADBMS_Abstraction.h"
#include "ADBMS_CMD_MAKROS.h"
#include "ADBMS_LL_Driver.h"
#include "can-halal.h"
#include "errors.h"
#include "stm32f3xx_hal.h"
#include <stdbool.h>
typedef enum {
AMSDEACTIVE,
AMSIDLE,
AMSCHARGING,
AMSIDLEBALANCING,
AMSDISCHARGING,
AMSWARNING,
AMSERROR
} amsState;
extern amsState currentAMSState;
extern Cell_Module module;
extern uint32_t balancedCells;
extern bool BalancingActive;
extern uint8_t numberofCells;
extern uint8_t numberofAux;
void AMS_Init(SPI_HandleTypeDef* hspi);
void AMS_Loop();
uint8_t AMS_Balancing_Loop();
uint8_t AMS_Idle_Loop();
uint8_t AMS_Warning_Loop();
uint8_t AMS_Error_Loop();
uint8_t AMS_Charging_Loop();
uint8_t AMS_Discharging_Loop();
#endif /* INC_AMS_HIGHLEVEL_H_ */

View File

@ -0,0 +1,45 @@
/*
* PWM_control.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#ifndef INC_PWM_CONTROL_H
#define INC_PWM_CONTROL_H
#include "stm32f3xx_hal.h"
#include "state_machine.h"
/* The PWM period (1/FPWM) is defined by the following parameters:
ARR value, the Prescaler value, and the internal clock itself which drives the timer module FCLK.
F_PWM = (F_CLK)/((ARR + 1) * (PSC + 1))
(ARR + 1) * (PSC + 1) = (F_CLK)/(F_PWM)
(PSC + 1) = (F_CLK)/(F_PWM * (ARR + 1))
F_CLK = 16 MHz
POWERGROUND ESC Signal: pulse every 20 ms, 1 ms = 0%, 2 ms = 100%
FREQ = 50 Hz -> 16 MHz/50 Hz = 320000 = ((39999 + 1) * (7 + 1))
DUTY CYCLE = 1/20 -> 0%, DUTY CYCLE = 2/20 -> 100%
CCR * DUTY_CYCLE
CCR: 1/20 -> 500, 2/20 -> 1000
*/
// UNUSED
#define POWERGROUND_FREQ 50
#define POWERGROUND_PRESCALER 7
#define POWERGROUND_ARR 39999
#define POWERGROUND_MIN_DUTY_CYCLE 0.05
#define POWERGROUND_MAX_DUTY_CYCLE 0.1
//#define BATTERY_COOLING_FREQ 20000
extern uint8_t current_powerground_status;
extern uint8_t target_powerground_status;
void PWM_control_init(TIM_HandleTypeDef* pg, TIM_HandleTypeDef* bat_cool, TIM_HandleTypeDef* esc_cool);
void PWM_powerground_softcontrol();
void PWM_powerground_control(uint8_t percent);
void PWM_battery_cooling_control(uint8_t percent);
#endif /* INC_CHANNEL_CONTROL_H */

View File

@ -0,0 +1,20 @@
#ifndef INC_TMP1075_H_
#define INC_TMP1075_H_
#include "stm32f3xx_hal.h"
#include "can-halal.h"
#include "errors.h"
#include <stdint.h>
#define N_CELLS 13
#define N_TEMP_SENSORS 13
extern uint32_t tmp1075_failed_sensors;
extern int16_t tmp1075_temps[N_TEMP_SENSORS];
HAL_StatusTypeDef tmp1075_init(I2C_HandleTypeDef* hi2c);
HAL_StatusTypeDef tmp1075_measure();
HAL_StatusTypeDef tmp1075_sensor_init(int n);
HAL_StatusTypeDef tmp1075_sensor_read(int n, int16_t* res);
#endif // INC_TMP1075_H_

29
Software/Core/Inc/can.h Normal file
View File

@ -0,0 +1,29 @@
/*
* can.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#ifndef INC_CAN_H
#define INC_CAN_H
#include "stm32f3xx_hal.h"
#include "main.h"
#include "can-halal.h"
#include "state_machine.h"
extern uint32_t can_status_timer, can_log_timer, can_timeout_timer;
void can_init(CAN_HandleTypeDef* hcan);
void can_handle_send_status();
void can_handle_send_log();
void can_handle_dump();
void can_handle_recieve_command(const uint8_t *data);
void ftcan_msg_received_cb(uint16_t id, size_t datalen, const uint8_t *data);
#endif /* "INC_CAN_H" */

33
Software/Core/Inc/eeprom.h Executable file
View File

@ -0,0 +1,33 @@
/*
* PWM_control.h
*
* Created on: 10.07.2024
* Author: Hamza
*/
#ifndef INC_EEPROM_H_
#define INC_EEPROM_H_
#include <stm32f3xx_hal.h>
#include "ADBMS_LL_Driver.h"
#include "soc_estimation.h"
#include <state_machine.h>
#include "stm32f3xx_hal_def.h"
#include "stm32f3xx_hal_i2c.h"
#include "TMP1075.h"
// see Datasheet for these values
#define EEPROM_I2C_ADDR 0xA4 // 0xA4 for the the first 2⁸ addresses and 0xA6 for the the last 2⁸ addresses
#define EERROM_MEMORY_ADDR_SIZE 2 // it is controlled by A17 in the address Byte, see datasheet
#define EEPROM_MEMORY_SIZE 131072 // in bytes
#define EEPROM_PAGE_SIZE 32 // in bytes
extern uint32_t write_address, read_address;
void eeprom_init(I2C_HandleTypeDef* hi2c);
void eeprom_write_status();
HAL_StatusTypeDef eeprom_read(uint8_t* data, uint16_t data_length);
HAL_StatusTypeDef eeprom_write(uint8_t* data, uint16_t data_length);
#endif // INC_EEPROM_H_

View File

@ -0,0 +1,41 @@
#ifndef INC_ERRORS_H
#define INC_ERRORS_H
#include <stdint.h>
#define ERROR_SOURCE_VOLTAGES (1 << 0)
#define ERROR_SOURCE_TEMPERATURES (1 << 1)
#define ERROR_SOURCE_TOO_FEW_WORKING_TEMP_SENSORS (1 << 2)
#define ERROR_SOURCE_OPEN_CELL_CONNECTION (1 << 3)
#define ERROR_SOURCE_EEPROM (1 << 4)
#define ERROR_SOURCE_INTERNAL (1 << 5)
#define ERROR_TIME_THRESH 150 // ms
typedef enum : uint16_t {
SEK_OVERTEMP = 0x0,
SEK_UNDERTEMP = 0x1,
SEK_OVERVOLT = 0x2,
SEK_UNDERVOLT = 0x3,
SEK_TOO_FEW_TEMPS = 0x4,
SEK_OPENWIRE = 0x5,
SEK_EEPROM_ERR = 0x6,
SEK_INTERNAL_BMS_TIMEOUT = 0x7,
SEK_INTERNAL_BMS_CHECKSUM_FAIL = 0x8,
SEK_INTERNAL_BMS_OVERTEMP = 0x9,
SEK_INTERNAL_BMS_FAULT = 0xA,
} SlaveErrorKind;
typedef struct {
uint16_t error_sources;
SlaveErrorKind data_kind;
uint8_t data[4];
uint32_t errors_since;
} SlaveErrorData;
extern SlaveErrorData error_data;
void set_error_source(SlaveErrorKind source);
void clear_error_source(SlaveErrorKind source);
#endif // INC_ERRORS_H

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

@ -0,0 +1,105 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.h
* @brief : Header for main.c file.
* This file contains the common defines of the application.
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f3xx_hal.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
/* Exported functions prototypes ---------------------------------------------*/
void Error_Handler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
#define CSB_Pin GPIO_PIN_4
#define CSB_GPIO_Port GPIOA
#define ESC_L_PWM_Pin GPIO_PIN_0
#define ESC_L_PWM_GPIO_Port GPIOB
#define ESC_R_PWM_Pin GPIO_PIN_1
#define ESC_R_PWM_GPIO_Port GPIOB
#define BAT_COOLING_PWM_Pin GPIO_PIN_10
#define BAT_COOLING_PWM_GPIO_Port GPIOB
#define BAT_COOLING_ENABLE_Pin GPIO_PIN_11
#define BAT_COOLING_ENABLE_GPIO_Port GPIOB
#define ESC_COOLING_ENABLE_Pin GPIO_PIN_14
#define ESC_COOLING_ENABLE_GPIO_Port GPIOB
#define ESC_COOLING_PWM_Pin GPIO_PIN_15
#define ESC_COOLING_PWM_GPIO_Port GPIOB
#define EEPROM___WC__Pin GPIO_PIN_8
#define EEPROM___WC__GPIO_Port GPIOA
#define EEPROM_SCL_Pin GPIO_PIN_9
#define EEPROM_SCL_GPIO_Port GPIOA
#define EEPROM_SDA_Pin GPIO_PIN_10
#define EEPROM_SDA_GPIO_Port GPIOA
#define TMP_SCL_Pin GPIO_PIN_15
#define TMP_SCL_GPIO_Port GPIOA
#define RELAY_ENABLE_Pin GPIO_PIN_4
#define RELAY_ENABLE_GPIO_Port GPIOB
#define PRECHARGE_ENABLE_Pin GPIO_PIN_5
#define PRECHARGE_ENABLE_GPIO_Port GPIOB
#define STATUS_LED_R_Pin GPIO_PIN_6
#define STATUS_LED_R_GPIO_Port GPIOB
#define STATUS_LED_G_Pin GPIO_PIN_7
#define STATUS_LED_G_GPIO_Port GPIOB
#define STATUS_LED_B_Pin GPIO_PIN_8
#define STATUS_LED_B_GPIO_Port GPIOB
#define TMP_SDA_Pin GPIO_PIN_9
#define TMP_SDA_GPIO_Port GPIOB
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
#ifdef __cplusplus
}
#endif
#endif /* __MAIN_H */

View File

@ -0,0 +1,21 @@
#ifndef INC_SOC_ESTIMATION_H
#define INC_SOC_ESTIMATION_H
#include "state_machine.h"
#include "stm32f3xx_hal.h"
#include <stddef.h>
#include <stdint.h>
extern float current_soc;
void soc_init();
void soc_update();
typedef struct {
uint16_t ocv;
float soc;
} ocv_soc_pair_t;
extern ocv_soc_pair_t OCV_SOC_PAIRS[];
float soc_for_ocv(uint16_t ocv);
#endif // INC_SOC_ESTIMATION_H

View File

@ -0,0 +1,98 @@
/*
* state_machine.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#ifndef INC_STATE_MACHINE_H
#define INC_STATE_MACHINE_H
#include "ADBMS_LL_Driver.h"
#include <AMS_HighLevel.h>
#include <can.h>
#include <eeprom.h>
#include <errors.h>
#include <PWM_control.h>
#include <status_LED.h>
#include <TMP1075.h>
#include <stdint.h>
#include <stdbool.h>
#include <math.h>
typedef enum { // states -> 3 bit. valid transitions: (all could transition to error)
STATE_INACTIVE, // INACTIVE -> PRECHARGE, CHARGING, ERROR
STATE_PRECHARGE, // PRECHARGE -> INACTIVE, READY, DISCHARGE, ERROR
STATE_READY, // READY -> ACTIVE, DISCHARGE, ERROR
STATE_ACTIVE, // ACTIVE -> READY, DISCHARGE, ERROR
STATE_DISCHARGE, // DISCHARGE -> INACTIVE, PRECHARGE, ERROR
STATE_CHARGING_PRECHARGE,
STATE_CHARGING, // CHARGING -> INACTIVE, DISCHARGE, ERROR
STATE_ERROR, // ERROR -> INACTIVE, DISCHARGE, ERROR
} State;
typedef struct {
uint16_t bms_timeout : 1;
uint16_t bms_fault : 1;
uint16_t temperature_error : 1;
uint16_t current_error : 1;
uint16_t current_sensor_missing : 1;
uint16_t voltage_error : 1;
uint16_t voltage_missing : 1;
uint16_t state_transition_fail : 1;
uint16_t eeprom_error : 1;
uint16_t : 7; // padding
} ErrorKind;
//typedef enum {} WarningKind;
typedef struct {
State current_state;
State target_state;
uint16_t error_source; // TSErrorSource (bitmask)
ErrorKind error_type; // TSErrorKind
} StateHandle;
typedef enum { RELAY_MAIN, RELAY_PRECHARGE } Relay;
extern StateHandle state;
extern bool programming_mode;
extern int32_t RELAY_BAT_SIDE_VOLTAGE;
extern int32_t RELAY_ESC_SIDE_VOLTAGE;
extern int32_t CURRENT_MEASUREMENT;
void sm_init();
void sm_update();
void sm_handle_ams_in(const uint8 *data);
void sm_precharge_discharge_manager();
void sm_powerground_manager();
void sm_calibrate_powerground();
void sm_balancing();
void sm_eeprom_write_status();
void sm_program_powerground();
void sm_check_errors();
void sm_set_error_source();
State sm_update_inactive();
State sm_update_precharge();
State sm_update_ready();
State sm_update_active();
State sm_update_discharge();
State sm_update_charging_precharge();
State sm_update_charging();
State sm_update_error();
void sm_set_relay_positions(State state);
void sm_set_relay(Relay relay, bool closed);
void sm_check_battery_temperature(uint8_t* id, uint16_t* temp);
void sm_check_battery_voltage(uint8_t* id, uint16_t* voltage);
int16_t sm_return_cell_temperature(int id);
int16_t sm_return_cell_voltage(int id);
void sm_test_cycle_states();
#endif /* "INC_STATE_MACHINE_H" */

View File

@ -0,0 +1,31 @@
/*
* status_LED.h
*
* Created on: 07.07.2024
* Author: Hamza
*/
#ifndef INC_STATUS_LED_H
#define INC_STATUS_LED_H
#include "stm32f3xx_hal.h"
#include <state_machine.h>
typedef enum {
OFF,
RED,
GREEN,
BLUE,
YELLOW,
PINK,
CYAN,
WHITE
} color;
void status_led_init(TIM_HandleTypeDef* r, TIM_HandleTypeDef* g, TIM_HandleTypeDef* b);
void status_led_update();
void status_led_set_color(color color);
void status_led_set(uint8_t r, uint8_t g, uint8_t b);
#endif /* "INC_STATUS_LED_H" */

View File

@ -0,0 +1,359 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f3xx_hal_conf.h
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* Copyright (c) 2016 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F3xx_HAL_CONF_H
#define __STM32F3xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
/*#define HAL_ADC_MODULE_ENABLED */
/*#define HAL_CRYP_MODULE_ENABLED */
#define HAL_CAN_MODULE_ENABLED
/*#define HAL_CEC_MODULE_ENABLED */
/*#define HAL_NAND_MODULE_ENABLED */
/*#define HAL_NOR_MODULE_ENABLED */
/*#define HAL_PCCARD_MODULE_ENABLED */
/*#define HAL_SRAM_MODULE_ENABLED */
/*#define HAL_HRTIM_MODULE_ENABLED */
/*#define HAL_OPAMP_MODULE_ENABLED */
/*#define HAL_SDADC_MODULE_ENABLED */
/*#define HAL_TSC_MODULE_ENABLED */
/*#define HAL_COMP_MODULE_ENABLED */
/*#define HAL_CRC_MODULE_ENABLED */
/*#define HAL_CRYP_MODULE_ENABLED */
/*#define HAL_DAC_MODULE_ENABLED */
/*#define HAL_I2S_MODULE_ENABLED */
/*#define HAL_IWDG_MODULE_ENABLED */
/*#define HAL_LCD_MODULE_ENABLED */
/*#define HAL_LPTIM_MODULE_ENABLED */
/*#define HAL_RNG_MODULE_ENABLED */
/*#define HAL_RTC_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
/*#define HAL_UART_MODULE_ENABLED */
/*#define HAL_USART_MODULE_ENABLED */
/*#define HAL_IRDA_MODULE_ENABLED */
/*#define HAL_SMARTCARD_MODULE_ENABLED */
/*#define HAL_SMBUS_MODULE_ENABLED */
/*#define HAL_WWDG_MODULE_ENABLED */
/*#define HAL_PCD_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
/* #define HAL_CAN_LEGACY_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
#define HAL_I2C_MODULE_ENABLED
/* ########################## HSE/HSI Values adaptation ##################### */
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)16000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
/**
* @brief In the following line adjust the External High Speed oscillator (HSE) Startup
* Timeout value
*/
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief In the following line adjust the Internal High Speed oscillator (HSI) Startup
* Timeout value
*/
#if !defined (HSI_STARTUP_TIMEOUT)
#define HSI_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSI start up */
#endif /* HSI_STARTUP_TIMEOUT */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE ((uint32_t)40000)
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature. */
/**
* @brief External Low Speed oscillator (LSE) value.
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */
/**
* @brief Time out for LSE start up value in ms.
*/
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for I2S peripheral
* This value is used by the I2S HAL module to compute the I2S clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
* - External clock generated through external PLL component on EVAL 303 (based on MCO or crystal)
* - External clock not generated on EVAL 373
*/
#if !defined (EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE ((uint32_t)8000000) /*!< 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 ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)15) /*!< tick interrupt priority (lowest by default) */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
#define INSTRUCTION_CACHE_ENABLE 0
#define DATA_CACHE_ENABLE 0
#define USE_SPI_CRC 0U
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */
#define USE_HAL_HRTIM_REGISTER_CALLBACKS 0U /* HRTIM register callback disabled */
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U /* OPAMP register callback disabled */
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
#define USE_HAL_TSC_REGISTER_CALLBACKS 0U /* TSC register callback disabled */
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f3xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f3xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32f3xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f3xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f3xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f3xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f3xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
#include "stm32f3xx_hal_can_legacy.h"
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f3xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32f3xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f3xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f3xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f3xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f3xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32f3xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32f3xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_PCCARD_MODULE_ENABLED
#include "stm32f3xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#ifdef HAL_HRTIM_MODULE_ENABLED
#include "stm32f3xx_hal_hrtim.h"
#endif /* HAL_HRTIM_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f3xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f3xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f3xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f3xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_OPAMP_MODULE_ENABLED
#include "stm32f3xx_hal_opamp.h"
#endif /* HAL_OPAMP_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f3xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f3xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f3xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SDADC_MODULE_ENABLED
#include "stm32f3xx_hal_sdadc.h"
#endif /* HAL_SDADC_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f3xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32f3xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f3xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f3xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32f3xx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f3xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f3xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f3xx_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 /* __STM32F3xx_HAL_CONF_H */

View File

@ -0,0 +1,68 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f3xx_it.h
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F3xx_IT_H
#define __STM32F3xx_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 USB_LP_CAN_RX0_IRQHandler(void);
void CAN_RX1_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F3xx_IT_H */