Compare commits

...

2 Commits

Author SHA1 Message Date
hamza
67466b72d5 empty branch for mvbms 2024-07-09 13:46:06 +03:00
c5c4184d6b balancing update 2024-07-08 17:50:17 +02:00
28 changed files with 305 additions and 2758 deletions

View File

@ -1,106 +0,0 @@
/*
* 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];
int16_t 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

@ -1,171 +0,0 @@
/*
* 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

@ -1,44 +0,0 @@
/*
* 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);
uint8 writeCMD(uint16 command, uint8* args, uint8 arglen);
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

@ -1,57 +0,0 @@
/*
* 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.h"
#include "TMP1075.h"
#include "can-halal.h"
#include "errors.h"
#include "stm32f3xx_hal.h"
#include <stdint.h>
typedef enum {
AMSDEACTIVE,
AMSIDLE,
AMSCHARGING,
AMSIDLEBALANCING,
AMSDISCHARGING,
AMSWARNING,
AMSERROR
} amsState;
extern amsState currentAMSState;
extern Cell_Module module;
extern uint32_t balancedCells;
extern uint8_t BalancingActive;
extern uint8_t stateofcharge;
extern uint8_t amserrorcode;
extern uint8_t amswarningcode;
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();
uint8_t writeWarningLog(uint8_t warningCode);
uint8_t writeErrorLog(uint8_t errorCode);
uint8_t integrateCurrent();
#endif /* INC_AMS_HIGHLEVEL_H_ */

View File

@ -1,32 +0,0 @@
#ifndef INC_PWM_CONTROL_H
#define INC_PWM_CONTROL_H
#include "stm32f3xx_hal.h"
#include "ADBMS_LL_Driver.h"
#include "state_machine.h"
#include <stdint.h>
#include "main.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))
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
*/
#define POWERGROUND_FREQ 50
//#define BATTERY_COOLING_FREQ 20000
void PWM_control_init(TIM_HandleTypeDef* powerground, TIM_HandleTypeDef* battery_cooling);
void PWM_powerground_control(uint8_t percent);
void PWM_battery_cooling_control(uint8_t percent);
void PWM_set_throttle();
#endif /* INC_CHANNEL_CONTROL_H */

View File

@ -1,20 +0,0 @@
#ifndef INC_TMP1075_H_
#define INC_TMP1075_H_
#include "can.h"
#include "common_defs.h"
#include "stm32f3xx_hal.h"
#include "TMP1075.h"
#include "can-halal.h"
#include "errors.h"
#include <stdint.h>
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_

View File

@ -1,23 +0,0 @@
#ifndef INC_CAN_H
#define INC_CAN_H
#include "stm32f3xx_hal.h"
#include "ADBMS_Abstraction.h"
#include "main.h"
#include "can-halal.h"
#include "AMS_HighLevel.h"
#include "state_machine.h"
#include <stdint.h>
#define CAN_ID_IN 0x501
#define CAN_ID_OUT 0x502
#define CAN_STATUS_FREQ 1000
void can_init(CAN_HandleTypeDef* hcan);
void can_handle_send_status();
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" */

View File

@ -1,14 +0,0 @@
/*
* common_defs.h
*
* Created on: 23 Mar 2022
* Author: Jasper
*/
#ifndef INC_COMMON_DEFS_H_
#define INC_COMMON_DEFS_H_
#define N_CELLS 12
#define N_TEMP_SENSORS 12
#endif /* INC_COMMON_DEFS_H_ */

View File

@ -1,41 +0,0 @@
#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 {
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 {
int error_sources;
SlaveErrorKind data_kind;
uint8_t data[4];
uint32_t errors_since;
} SlaveErrorData;
extern SlaveErrorData error_data;
void set_error_source(int source);
void clear_error_source(int source);
#endif // INC_ERRORS_H

View File

@ -77,8 +77,10 @@ void Error_Handler(void);
#define STATUS_LED_G_GPIO_Port GPIOB
#define PRECHARGE_EN_Pin GPIO_PIN_11
#define PRECHARGE_EN_GPIO_Port GPIOB
#define PWM_Battery_Cooling_Pin GPIO_PIN_15
#define PWM_Battery_Cooling_GPIO_Port GPIOB
#define AUX_IN_Pin GPIO_PIN_13
#define AUX_IN_GPIO_Port GPIOB
#define AUX_OUT_Pin GPIO_PIN_14
#define AUX_OUT_GPIO_Port GPIOB
#define RELAY_BATT_SIDE_ON_Pin GPIO_PIN_8
#define RELAY_BATT_SIDE_ON_GPIO_Port GPIOA
#define RELAY_ESC_SIDE_ON_Pin GPIO_PIN_9

View File

@ -1,96 +0,0 @@
#ifndef INC_STATE_MACHINE_H
#define INC_STATE_MACHINE_H
#include <stdint.h>
#include <stdbool.h>
#include "ADBMS_LL_Driver.h"
#include "AMS_HighLevel.h"
#include "errors.h"
#include "PWM_control.h"
#include "TMP1075.h"
#include <math.h>
// Minimum vehicle side voltage to exit precharge
#define MIN_VEHICLE_SIDE_VOLTAGE 150000 // mV
// Time to wait after reaching 95% of battery voltage before exiting precharge
// Set this to 1000 in scruti to demonstrate the voltage on the multimeter
#define PRECHARGE_95_DURATION 0 // ms
// Time to wait for discharge
#define DISCHARGE_DURATION 5000 // ms
// Time to wait after there is no more error condition before exiting TS_ERROR
#define NO_ERROR_TIME 1000 // ms
// Time to wait for charger voltage before going to TS_ERROR
#define MAX_CHARGING_CHECK_DURATION 2000 // ms
// Time to wait between closing relays
#define RELAY_CLOSE_WAIT 10 // ms
#warning
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;
} ErrorKind;
//typedef enum {} WarningKind;
typedef struct {
State current_state;
State target_state;
uint16_t error_source; // TSErrorSource (bitmask)
ErrorKind error_type; // TSErrorKind
} StateHandle;
extern StateHandle state;
static bool relay_closed = 0;
static bool precharge_closed = 0;
extern int16_t RELAY_BAT_SIDE_VOLTAGE;
extern int16_t RELAY_ESC_SIDE_VOLTAGE;
extern int16_t CURRENT_MEASUREMENT;
extern uint8_t powerground_status;
void sm_init();
void sm_update();
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();
typedef enum { RELAY_MAIN, RELAY_PRECHARGE } Relay;
void sm_set_relay_positions(State state);
void sm_set_relay(Relay relay, bool closed);
void sm_check_charging();
void sm_check_battery_temperature(int8_t* id, int16_t* temp);
int16_t sm_return_cell_temperature(int id);
int16_t sm_return_cell_voltage(int id);
void sm_handle_ams_in(const uint8 *data);
void sm_check_errors();
void sm_set_error(ErrorKind error_kind, bool is_errored);
void sm_test_cycle_states();
#endif /* "INC_STATE_MACHINE_H" */

View File

@ -81,7 +81,7 @@
* (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 */
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
/**

View File

@ -55,8 +55,6 @@ 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 */

View File

@ -1,246 +0,0 @@
/*
* ADBMS_Abstraction.c
*
* Created on: 14.07.2022
* Author: max
*/
#include "ADBMS_Abstraction.h"
#include "ADBMS_CMD_MAKROS.h"
#include "ADBMS_LL_Driver.h"
#include <stddef.h>
uint8 numberofcells;
uint8 numberofauxchannels;
#define CHECK_RETURN(x) \
{ \
uint8 status = x; \
if (status != 0) \
return status; \
}
uint8 amsReset() {
amsWakeUp();
readCMD(SRST, NULL, 0);
mcuDelay(10);
amsWakeUp();
amsStopBalancing();
amsConfigOverUnderVoltage(DEFAULT_OV, DEFAULT_UV);
uint8 buffer[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
CHECK_RETURN(writeCMD(CLRFLAG, buffer, 6)); //clear flags,
CHECK_RETURN(writeCMD(CLOVUV, buffer, 6)); //OVUV flags
CHECK_RETURN(writeCMD(ADCV | ADCV_CONT | ADCV_RD, NULL, 0)); //start continuous cell voltage measurement with redundancy
CHECK_RETURN(writeCMD(ADAX | ADAX_CONV_ALL, NULL, 0)); //start aux measurement
return 0;
}
uint8 initAMS(SPI_HandleTypeDef* hspi, uint8 numofcells, uint8 numofaux) {
adbmsDriverInit(hspi);
numberofcells = numofcells;
numberofauxchannels = numofaux;
return amsReset();
}
uint8 amsWakeUp() {
uint8 buf[6];
return readCMD(RDCFGA, buf, 6);
}
uint8 amsCellMeasurement(Cell_Module* module) {
#warning check conversion counter to ensure that continous conversion has not been stopped
#warning check for OW conditions: ADSV | ADSV_OW_0 / ADSV_OW_1
return amsReadCellVoltages(module);
}
uint8 amsConfigCellMeasurement(uint8 numberofChannels) {
numberofcells = numberofChannels;
return 0;
}
uint8 amsAuxAndStatusMeasurement(Cell_Module* module) {
uint8 rxbuf[AUX_GROUP_A_SIZE] = {};
CHECK_RETURN(readCMD(RDSTATC, rxbuf, STATUS_GROUP_C_SIZE));
module->status.CS_FLT = rxbuf[0] | (rxbuf[1] << 8);
module->status.CCTS = rxbuf[2] | (rxbuf[3] << 8);
module->status.VA_OV = (rxbuf[4] >> 7) & 0x01;
module->status.VA_UV = (rxbuf[4] >> 6) & 0x01;
module->status.VD_OV = (rxbuf[4] >> 5) & 0x01;
module->status.VD_UV = (rxbuf[4] >> 4) & 0x01;
module->status.CED = (rxbuf[4] >> 3) & 0x01;
module->status.CMED = (rxbuf[4] >> 2) & 0x01;
module->status.SED = (rxbuf[4] >> 1) & 0x01;
module->status.SMED = (rxbuf[4] >> 0) & 0x01;
module->status.VDEL = (rxbuf[5] >> 7) & 0x01;
module->status.VDE = (rxbuf[5] >> 6) & 0x01;
module->status.COMPARE= (rxbuf[5] >> 5) & 0x01;
module->status.SPIFLT = (rxbuf[5] >> 4) & 0x01;
module->status.SLEEP = (rxbuf[5] >> 3) & 0x01;
module->status.THSD = (rxbuf[5] >> 2) & 0x01;
module->status.TMODCHK= (rxbuf[5] >> 1) & 0x01;
module->status.OSCCHK = (rxbuf[5] >> 0) & 0x01;
if (pollCMD(PLAUX) == 0x0) { //TODO: check for SPI fault
return 0; // aux ADC data not ready
}
CHECK_RETURN(readCMD(RDAUXA, rxbuf, AUX_GROUP_A_SIZE));
module->auxVoltages[0] = mV_from_ADBMS6830(rxbuf[0] | (rxbuf[1] << 8));
module->auxVoltages[1] = mV_from_ADBMS6830(rxbuf[2] | (rxbuf[3] << 8));
module->auxVoltages[2] = mV_from_ADBMS6830(rxbuf[4] | (rxbuf[5] << 8));
CHECK_RETURN(readCMD(RDAUXB, rxbuf, AUX_GROUP_A_SIZE));
module->auxVoltages[3] = mV_from_ADBMS6830(rxbuf[0] | (rxbuf[1] << 8));
module->auxVoltages[4] = mV_from_ADBMS6830(rxbuf[2] | (rxbuf[3] << 8));
module->auxVoltages[5] = mV_from_ADBMS6830(rxbuf[4] | (rxbuf[5] << 8));
CHECK_RETURN(readCMD(RDAUXC, rxbuf, AUX_GROUP_A_SIZE));
module->auxVoltages[6] = mV_from_ADBMS6830(rxbuf[0] | (rxbuf[1] << 8));
module->auxVoltages[7] = mV_from_ADBMS6830(rxbuf[2] | (rxbuf[3] << 8));
module->auxVoltages[8] = mV_from_ADBMS6830(rxbuf[4] | (rxbuf[5] << 8));
CHECK_RETURN(readCMD(RDAUXD, rxbuf, AUX_GROUP_A_SIZE));
module->auxVoltages[9] = mV_from_ADBMS6830(rxbuf[0] | (rxbuf[1] << 8));
uint8 rxbuffer[STATUS_GROUP_A_SIZE];
CHECK_RETURN(readCMD(RDSTATA, rxbuffer, STATUS_GROUP_A_SIZE));
module->internalDieTemp = rxbuffer[2] | (rxbuffer[3] << 8);
CHECK_RETURN(readCMD(RDSTATB, rxbuffer, STATUS_GROUP_B_SIZE));
module->digitalSupplyVoltage = mV_from_ADBMS6830(rxbuffer[0] | (rxbuffer[1] << 8));
module->analogSupplyVoltage = mV_from_ADBMS6830(rxbuffer[2] | (rxbuffer[3] << 8));
module->refVoltage = mV_from_ADBMS6830(rxbuffer[4] | (rxbuffer[5] << 8));
CHECK_RETURN(writeCMD(ADAX | ADAX_CONV_ALL, NULL, 0)); //start aux measurement for next cycle
return 0;
}
uint8 amsConfigBalancing(uint32 channels, uint8 dutyCycle) {
uint8 buffer_a[PWM_GROUP_A_SIZE] = {};
uint8 buffer_b[PWM_GROUP_B_SIZE] = {};
CHECK_RETURN(readCMD(RDPWMA, buffer_a, CFG_GROUP_A_SIZE));
CHECK_RETURN(readCMD(RDPWMB, buffer_b, CFG_GROUP_B_SIZE));
if (dutyCycle > 0x0F) { // there are only 4 bits for duty cycle
return 1;
}
#warning fixme
for (size_t i = 0; i < 16; i += 2) {
if (i < 12) { // cells 0, 1 are in regbuffer[0], cells 2, 3 in regbuffer[1], ...
buffer_a[i / 2] = ((channels & (1 << (i + 1))) ? (dutyCycle << 4) : 0) |
((channels & (1 << i)) ? dutyCycle : 0);
} else {
buffer_b[(i - 12) / 2] = ((channels & (1 << (i + 1))) ? (dutyCycle << 4) : 0) |
((channels & (1 << i)) ? dutyCycle : 0);
}
}
CHECK_RETURN(writeCMD(WRPWMA, buffer_a, CFG_GROUP_A_SIZE));
CHECK_RETURN(writeCMD(WRPWMB, buffer_b, CFG_GROUP_B_SIZE));
return 0;
}
uint8 amsStartBalancing(uint8 dutyCycle) { return writeCMD(UNMUTE, NULL, 0); }
uint8 amsStopBalancing() { return writeCMD(MUTE, NULL, 0); }
uint8 amsSelfTest() { return 0; }
uint8 amsConfigOverUnderVoltage(uint16 overVoltage, uint16 underVoltage) {
uint8 buffer[CFG_GROUP_A_SIZE];
if (underVoltage & 0xF000 || overVoltage & 0xF000) { // only 12 bits allowed
return 1;
}
CHECK_RETURN(readCMD(RDCFGB, buffer, CFG_GROUP_A_SIZE));
//UV
buffer[0] = (uint8) (underVoltage & 0xFF);
buffer[1] &= 0xF0;
buffer[1] |= (uint8) ((underVoltage >> 8) & 0x0F);
//OV
buffer[1] &= 0x0F;
buffer[1] |= (uint8) (overVoltage << 4);
buffer[2] = (uint8) (overVoltage >> 4);
return writeCMD(WRCFGB, buffer, CFG_GROUP_A_SIZE);
}
uint8 amsCheckUnderOverVoltage(Cell_Module* module) {
uint8 regbuffer[STATUS_GROUP_D_SIZE];
uint32 ov_uv_data = 0;
CHECK_RETURN(readCMD(RDSTATD, regbuffer, STATUS_GROUP_D_SIZE));
ov_uv_data = (regbuffer[0] << 0) | (regbuffer[1] << 8) |
(regbuffer[2] << 16) | (regbuffer[3] << 24);
module->overVoltage = 0;
module->underVoltage = 0;
for (size_t i = 0; i < numberofcells; i++) { // ov/uv flags are 1-bit flags for each cell C0UV, C0OV, C1UV, C1OV, ...
module->underVoltage |= (ov_uv_data >> (i * 2)) & 0x01;
module->overVoltage |= (ov_uv_data >> (i * 2 + 1)) & 0x01;
}
return 0;
}
uint8 amsClearAux() {
uint8 buffer[6];
return writeCMD(CLRAUX, buffer, 0);
}
uint8 amsClearCells() {
uint8 buffer[6];
return writeCMD(CLRCELL, buffer, 0);
}
uint8 amsReadCellVoltages(Cell_Module* module) {
uint8 rxbuffer[CV_GROUP_A_SIZE];
CHECK_RETURN(readCMD(RDCVA, rxbuffer, CV_GROUP_A_SIZE));
module->cellVoltages[0] = mV_from_ADBMS6830(rxbuffer[0] | (rxbuffer[1] << 8));
module->cellVoltages[1] = mV_from_ADBMS6830(rxbuffer[2] | (rxbuffer[3] << 8));
module->cellVoltages[2] = mV_from_ADBMS6830(rxbuffer[4] | (rxbuffer[5] << 8));
CHECK_RETURN(readCMD(RDCVB, rxbuffer, CV_GROUP_A_SIZE));
module->cellVoltages[3] = mV_from_ADBMS6830(rxbuffer[0] | (rxbuffer[1] << 8));
module->cellVoltages[4] = mV_from_ADBMS6830(rxbuffer[2] | (rxbuffer[3] << 8));
module->cellVoltages[5] = mV_from_ADBMS6830(rxbuffer[4] | (rxbuffer[5] << 8));
CHECK_RETURN(readCMD(RDCVC, rxbuffer, CV_GROUP_A_SIZE));
module->cellVoltages[6] = mV_from_ADBMS6830(rxbuffer[0] | (rxbuffer[1] << 8));
module->cellVoltages[7] = mV_from_ADBMS6830(rxbuffer[2] | (rxbuffer[3] << 8));
module->cellVoltages[8] = mV_from_ADBMS6830(rxbuffer[4] | (rxbuffer[5] << 8));
CHECK_RETURN(readCMD(RDCVD, rxbuffer, CV_GROUP_A_SIZE));
module->cellVoltages[9] = mV_from_ADBMS6830(rxbuffer[0] | (rxbuffer[1] << 8));
module->cellVoltages[10] = mV_from_ADBMS6830(rxbuffer[2] | (rxbuffer[3] << 8));
module->cellVoltages[11] = mV_from_ADBMS6830(rxbuffer[4] | (rxbuffer[5] << 8));
CHECK_RETURN(readCMD(RDCVE, rxbuffer, CV_GROUP_A_SIZE));
module->cellVoltages[12] = mV_from_ADBMS6830(rxbuffer[0] | (rxbuffer[1] << 8));
module->cellVoltages[13] = mV_from_ADBMS6830(rxbuffer[2] | (rxbuffer[3] << 8));
module->cellVoltages[14] = mV_from_ADBMS6830(rxbuffer[4] | (rxbuffer[5] << 8));
CHECK_RETURN(readCMD(RDCVF, rxbuffer, CV_GROUP_A_SIZE));
module->cellVoltages[15] = mV_from_ADBMS6830(rxbuffer[0] | (rxbuffer[1] << 8));
return 0;
}

View File

@ -1,361 +0,0 @@
/*
* ADBMS_LL_Driver.c
*
* Created on: 05.06.2022
* Author: max
*/
#include "ADBMS_LL_Driver.h"
#include <stdbool.h>
#define INITIAL_COMMAND_PEC 0x0010
#define INITIAL_DATA_PEC 0x0010
#define ADBMS_SPI_TIMEOUT 100 // Timeout in ms
#warning ask about the timeout value
SPI_HandleTypeDef* adbmsspi;
uint8 adbmsDriverInit(SPI_HandleTypeDef* hspi) {
mcuAdbmsCSLow();
HAL_Delay(1);
mcuAdbmsCSHigh();
adbmsspi = hspi;
return 0;
}
//command PEC calculation
//CRC-15
//x^15 + x^14 + x^10 + x^8 + x^7 + x^4 + x^3 + 1
uint8 calculateCommandPEC(uint8_t* data, uint8_t datalen) {
uint16 currentpec = INITIAL_COMMAND_PEC;
if (datalen >= 3) {
for (int i = 0; i < (datalen - 2); i++) {
for (int n = 0; n < 8; n++) {
uint8 din = data[i] << (n);
currentpec = updateCommandPEC(currentpec, din);
}
}
data[datalen - 2] = (currentpec >> 7) & 0xFF;
data[datalen - 1] = (currentpec << 1) & 0xFF;
return 0;
} else {
return 1;
}
}
uint8 checkCommandPEC(uint8* data, uint8 datalen) {
if (datalen <= 3) {
return 255;
}
uint16 currentpec = INITIAL_COMMAND_PEC;
for (int i = 0; i < (datalen - 2); i++) {
for (int n = 0; n < 8; n++) {
uint8 din = data[i] << (n);
currentpec = updateCommandPEC(currentpec, din);
}
}
uint8 pechigh = (currentpec >> 7) & 0xFF;
uint8 peclow = (currentpec << 1) & 0xFF;
if ((pechigh == data[datalen - 2]) && (peclow == data[datalen - 1])) {
return 0;
}
return 1;
}
uint16 updateCommandPEC(uint16 currentPEC, uint8 din) {
din = (din >> 7) & 0x01;
uint8 in0 = din ^ ((currentPEC >> 14) & 0x01);
uint8 in3 = in0 ^ ((currentPEC >> 2) & 0x01);
uint8 in4 = in0 ^ ((currentPEC >> 3) & 0x01);
uint8 in7 = in0 ^ ((currentPEC >> 6) & 0x01);
uint8 in8 = in0 ^ ((currentPEC >> 7) & 0x01);
uint8 in10 = in0 ^ ((currentPEC >> 9) & 0x01);
uint8 in14 = in0 ^ ((currentPEC >> 13) & 0x01);
uint16 newPEC = 0;
newPEC |= in14 << 14;
newPEC |= (currentPEC & (0x01 << 12)) << 1;
newPEC |= (currentPEC & (0x01 << 11)) << 1;
newPEC |= (currentPEC & (0x01 << 10)) << 1;
newPEC |= in10 << 10;
newPEC |= (currentPEC & (0x01 << 8)) << 1;
newPEC |= in8 << 8;
newPEC |= in7 << 7;
newPEC |= (currentPEC & (0x01 << 5)) << 1;
newPEC |= (currentPEC & (0x01 << 4)) << 1;
newPEC |= in4 << 4;
newPEC |= in3 << 3;
newPEC |= (currentPEC & (0x01 << 1)) << 1;
newPEC |= (currentPEC & (0x01)) << 1;
newPEC |= in0;
return newPEC;
}
//data PEC calculation
//CRC-10
//x^10 + x^7 + x^3 + x^2 + x + 1
uint16_t pec10_calc(bool rx_cmd, int len, uint8_t* data) {
uint16_t remainder = 16; /* PEC_SEED; 0000010000 */
uint16_t polynom = 0x8F; /* x10 + x7 + x3 + x2 + x + 1 <- the CRC15 polynomial
100 1000 1111 48F */
/* Perform modulo-2 division, a byte at a time. */
for (uint8_t pbyte = 0; pbyte < len; ++pbyte) {
/* Bring the next byte into the remainder. */
remainder ^= (uint16_t)(data[pbyte] << 2);
/* Perform modulo-2 division, a bit at a time.*/
for (uint8_t bit_ = 8; bit_ > 0; --bit_) {
/* Try to divide the current data bit. */
if ((remainder & 0x200) >
0) // equivalent to remainder & 2^14 simply check for MSB
{
remainder = (uint16_t)((remainder << 1));
remainder = (uint16_t)(remainder ^ polynom);
} else {
remainder = (uint16_t)(remainder << 1);
}
}
}
if (rx_cmd == true) {
remainder ^= (uint16_t)((data[len] & 0xFC) << 2);
/* Perform modulo-2 division, a bit at a time */
for (uint8_t bit_ = 6; bit_ > 0; --bit_) {
/* Try to divide the current data bit */
if ((remainder & 0x200) >
0) // equivalent to remainder & 2^14 simply check for MSB
{
remainder = (uint16_t)((remainder << 1));
remainder = (uint16_t)(remainder ^ polynom);
} else {
remainder = (uint16_t)((remainder << 1));
}
}
}
return ((uint16_t)(remainder & 0x3FF));
}
typedef uint16_t crc;
crc F_CRC_CalculaCheckSum(uint8_t const AF_Datos[], uint16_t VF_nBytes);
uint8 calculateDataPEC(uint8_t* data, uint8_t datalen) {
if (datalen >= 3) {
crc currentpec = pec10_calc(true, datalen - 2, data) & 0x3FF; // mask to 10 bits
// memory layout is [[zeroes], PEC[9:8]], [PEC[7:0]]
data[datalen - 2] = (currentpec >> 8) & 0xFF;
data[datalen - 1] = currentpec & 0xFF;
volatile uint8 result = pec10_calc(true, datalen, data);
return 0;
} else {
return 1;
}
}
uint8 checkDataPEC(uint8* data, uint8 len) {
if (len <= 2) {
return 255;
}
crc currentpec = F_CRC_CalculaCheckSum(data, len);
return (currentpec == 0) ? 0 : 1;
}
static crc F_CRC_ObtenValorDeTabla(uint8_t VP_Pos_Tabla) {
crc VP_CRCTableValue = 0;
uint8_t VP_Pos_bit = 0;
VP_CRCTableValue = ((crc)(VP_Pos_Tabla)) << (10 - 8);
for (VP_Pos_bit = 0; VP_Pos_bit < 8; VP_Pos_bit++) {
if (VP_CRCTableValue & (((crc)1) << (10 - 1))) {
VP_CRCTableValue = (VP_CRCTableValue << 1) ^ 0x8F;
} else {
VP_CRCTableValue = (VP_CRCTableValue << 1);
}
}
return ((VP_CRCTableValue));
}
crc F_CRC_CalculaCheckSum(uint8_t const AF_Datos[], uint16_t VF_nBytes) {
crc VP_CRCTableValue = 16;
int16_t VP_bytes = 0;
for (VP_bytes = 0; VP_bytes < VF_nBytes; VP_bytes++) {
VP_CRCTableValue = (VP_CRCTableValue << 8) ^
F_CRC_ObtenValorDeTabla(
((uint8_t)((VP_CRCTableValue >> (10 - 8)) & 0xFF)) ^
AF_Datos[VP_bytes]);
}
if ((8 * sizeof(crc)) > 10) {
VP_CRCTableValue = VP_CRCTableValue & ((((crc)(1)) << 10) - 1);
}
return (VP_CRCTableValue ^ 0x0000);
}
uint16 updateDataPEC(uint16 currentPEC, uint8 din) {
din = (din >> 7) & 0x01;
uint8 in0 = din ^ ((currentPEC >> 9) & 0x01);
uint8 in2 = in0 ^ ((currentPEC >> 1) & 0x01);
uint8 in3 = in0 ^ ((currentPEC >> 2) & 0x01);
uint8 in7 = in0 ^ ((currentPEC >> 6) & 0x01);
uint16 newPEC = 0;
newPEC |= (currentPEC & (0x01 << 8)) << 1;
newPEC |= (currentPEC & (0x01 << 7)) << 1;
newPEC |= in7 << 7;
newPEC |= (currentPEC & (0x01 << 5)) << 1;
newPEC |= (currentPEC & (0x01 << 4)) << 1;
newPEC |= in3 << 3;
newPEC |= in2 << 2;
newPEC |= (currentPEC & (0x01)) << 1;
newPEC |= in0;
return newPEC;
}
uint8 writeCMD(uint16 command, uint8* args, uint8 arglen) {
uint8 ret;
if (arglen > 0) {
uint8 buffer[6 + arglen]; //command + PEC (2 bytes) + data + DPEC (2 bytes)
buffer[0] = (command >> 8) & 0xFF;
buffer[1] = (command) & 0xFF;
calculateCommandPEC(buffer, 4);
for (uint8 i = 0; i < arglen; i++) {
buffer[4 + i] = args[i];
}
calculateDataPEC(&buffer[4], arglen + 2); //DPEC is calculated over the data, not the command, and placed at the end of the data
mcuAdbmsCSLow();
ret = mcuSPITransmit(buffer, 6 + arglen);
mcuAdbmsCSHigh();
} else {
uint8 buffer[4];
buffer[0] = (command >> 8) & 0xFF;
buffer[1] = (command) & 0xFF;
calculateCommandPEC(buffer, 4);
mcuAdbmsCSLow();
ret = mcuSPITransmit(buffer, 4);
mcuAdbmsCSHigh();
}
return ret;
}
#define ITER_COUNT 50
static uint8_t count = 0;
static bool isOn = false;
uint8 readCMD(uint16 command, uint8* buffer, uint8 buflen) {
if (count == ITER_COUNT) {
HAL_GPIO_WritePin(STATUS_LED_B_GPIO_Port, STATUS_LED_B_Pin, isOn ? GPIO_PIN_SET : GPIO_PIN_RESET);
count = 0;
isOn = !isOn;
} else {
count++;
}
uint8 txbuffer[6 + buflen] = {};
uint8 rxbuffer[6 + buflen] = {};
txbuffer[0] = (command >> 8) & 0xFF;
txbuffer[1] = (command)&0xFF;
calculateCommandPEC(txbuffer, 4);
mcuAdbmsCSLow();
uint8 status = mcuSPITransmitReceive(rxbuffer, txbuffer, 6 + buflen);
mcuAdbmsCSHigh();
if (status != 0) {
return status;
}
for (uint8 i = 0; i < buflen; i++) {
buffer[i] = rxbuffer[i + 4];
}
[[maybe_unused]] uint8 commandCounter = rxbuffer[sizeof(rxbuffer) - 2] & 0xFC; //command counter is bits 7-2
//TODO: check command counter?
return checkDataPEC(&rxbuffer[4], buflen + 2);
}
//check poll command - no data PEC sent back
uint8 pollCMD(uint16 command) {
uint8 txbuffer[5] = {};
uint8 rxbuffer[5] = {};
txbuffer[0] = (command >> 8) & 0xFF;
txbuffer[1] = (command)&0xFF;
calculateCommandPEC(txbuffer, 4);
mcuAdbmsCSLow();
uint8 status = mcuSPITransmitReceive(rxbuffer, txbuffer, 5);
mcuAdbmsCSHigh();
if (status != 0) {
return status;
}
return rxbuffer[4]; //last byte will be poll response
}
void mcuAdbmsCSLow() {
HAL_GPIO_WritePin(CSB_GPIO_Port, CSB_Pin, GPIO_PIN_RESET);
}
void mcuAdbmsCSHigh() {
HAL_GPIO_WritePin(CSB_GPIO_Port, CSB_Pin, GPIO_PIN_SET);
}
uint8 mcuSPITransmit(uint8* buffer, uint8 buffersize) {
HAL_StatusTypeDef status;
uint8 rxbuf[buffersize];
status = HAL_SPI_TransmitReceive(adbmsspi, buffer, rxbuf, buffersize,
ADBMS_SPI_TIMEOUT);
__HAL_SPI_CLEAR_OVRFLAG(adbmsspi);
return status;
}
uint8 mcuSPIReceive(uint8* buffer, uint8 buffersize) {
HAL_StatusTypeDef status;
status = HAL_SPI_Receive(adbmsspi, buffer, buffersize, ADBMS_SPI_TIMEOUT);
return status;
}
uint8 mcuSPITransmitReceive(uint8* rxbuffer, uint8* txbuffer,
uint8 buffersize) {
HAL_StatusTypeDef status;
status = HAL_SPI_TransmitReceive(adbmsspi, txbuffer, rxbuffer, buffersize,
ADBMS_SPI_TIMEOUT);
return status;
}
inline void mcuDelay(uint16 delay) { HAL_Delay(delay); }

View File

@ -1,313 +0,0 @@
/*
* AMS_HighLevel.c
*
* Created on: 20.07.2022
* Author: max
*/
#include "AMS_HighLevel.h"
Cell_Module module = {};
uint32_t balancedCells = 0;
uint8_t BalancingActive = 0;
uint8_t stateofcharge = 100;
int64_t currentintegrator = 0;
uint32_t lastticks = 0;
uint32_t currenttick = 0;
uint8_t eepromconfigured = 0;
uint8_t internalbalancingalgo = 1;
uint16_t startbalancingthreshold = 41000;
uint16_t stopbalancingthreshold = 30000;
uint16_t balancingvoltagedelta = 10;
uint16_t amsuv = 0;
uint16_t amsov = 0;
uint8_t amserrorcode = 0;
uint8_t amswarningcode = 0;
uint8_t numberofCells = 14;
uint8_t numberofAux = 0;
uint8_t packetChecksumFails = 0;
#define MAX_PACKET_CHECKSUM_FAILS 5
uint8_t deviceSleeps = 0;
#define MAX_DEVICE_SLEEP 3 //TODO: change to correct value
amsState currentAMSState = AMSDEACTIVE;
amsState lastAMSState = AMSDEACTIVE;
struct pollingTimes {
uint32_t S_ADC_OW_CHECK;
uint32_t TMP1075;
};
struct pollingTimes pollingTimes = {0, 0};
void AMS_Init(SPI_HandleTypeDef* hspi) {
if (eepromconfigured == 1) {
/*amsov = eepromcellovervoltage>>4;
amsuv = (eepromcellundervoltage-1)>>4;
numberofCells = eepromnumofcells;
numberofAux = eepromnumofaux;
initAMS(hspi, eepromnumofcells, eepromnumofaux);*/
amsConfigOverUnderVoltage(amsov, amsuv);
} else {
initAMS(hspi, numberofCells, numberofAux);
amsov = DEFAULT_OV;
amsuv = DEFAULT_UV;
}
pollingTimes = (struct pollingTimes) {HAL_GetTick(), HAL_GetTick()};
currentAMSState = AMSIDLE;
}
void AMS_Loop() {
// On Transition Functions called ones if the State Changed
if (currentAMSState != lastAMSState) {
switch (currentAMSState) {
case AMSIDLE:
break;
case AMSDEACTIVE:
break;
case AMSCHARGING:
break;
case AMSIDLEBALANCING:
break;
case AMSDISCHARGING:
break;
case AMSWARNING:
writeWarningLog(0x01);
break;
case AMSERROR:
writeErrorLog(amserrorcode);
break;
}
lastAMSState = currentAMSState;
}
// Main Loops for different AMS States
switch (currentAMSState) {
case AMSIDLE:
AMS_Idle_Loop();
break;
case AMSDEACTIVE:
break;
case AMSCHARGING:
break;
case AMSIDLEBALANCING:
AMS_Idle_Loop();
break;
case AMSDISCHARGING:
break;
case AMSWARNING:
AMS_Warning_Loop();
break;
case AMSERROR:
break;
}
}
uint8_t AMS_Idle_Loop() {
if (!amsWakeUp()) {
//error_data.data_kind = SEK_INTERNAL_BMS_TIMEOUT;
//set_error_source(ERROR_SOURCE_INTERNAL);
}
packetChecksumFails += amsAuxAndStatusMeasurement(&module);
if (module.status.SLEEP) {
deviceSleeps++;
if (deviceSleeps > MAX_DEVICE_SLEEP) {
error_data.data_kind = SEK_INTERNAL_BMS_TIMEOUT;
set_error_source(ERROR_SOURCE_INTERNAL);
} else {
amsReset();
}
}
if (module.status.CS_FLT || module.status.SPIFLT || module.status.CMED ||
module.status.SMED || module.status.VDE || module.status.VDEL ||
module.status.OSCCHK || module.status.TMODCHK) {
error_data.data_kind = SEK_INTERNAL_BMS_FAULT;
set_error_source(ERROR_SOURCE_INTERNAL);
}
if (module.status.THSD) {
error_data.data_kind = SEK_INTERNAL_BMS_OVERTEMP;
set_error_source(ERROR_SOURCE_INTERNAL);
}
packetChecksumFails += amsCellMeasurement(&module);
packetChecksumFails += amsCheckUnderOverVoltage(&module);
packetChecksumFails += integrateCurrent();
if (packetChecksumFails > MAX_PACKET_CHECKSUM_FAILS) {
error_data.data_kind = SEK_INTERNAL_BMS_CHECKSUM_FAIL;
set_error_source(ERROR_SOURCE_INTERNAL);
}
tmp1075_measure();
int any_voltage_error = 0;
for (size_t i = 0; i < numberofCells; i++) {
if (module.cellVoltages[i] < 2500) {
any_voltage_error = 1;
error_data.data_kind = SEK_UNDERVOLT;
error_data.data[0] = i;
uint8_t* ptr = &error_data.data[1];
ptr = ftcan_marshal_unsigned(ptr, module.cellVoltages[i], 2);
} else if (module.cellVoltages[i] > 4200) {
any_voltage_error = 1;
error_data.data_kind = SEK_OVERVOLT;
error_data.data[0] = i;
uint8_t* ptr = &error_data.data[1];
ptr = ftcan_marshal_unsigned(ptr, module.cellVoltages[i], 2);
}
}
if (module.internalDieTemp > 28000) { //TODO: change to correct value
error_data.data_kind = SEK_INTERNAL_BMS_OVERTEMP;
uint8_t* ptr = &error_data.data[0];
ptr = ftcan_marshal_unsigned(ptr, module.internalDieTemp, 2);
set_error_source(ERROR_SOURCE_INTERNAL);
} else {
clear_error_source(ERROR_SOURCE_INTERNAL);
}
if (any_voltage_error) {
set_error_source(ERROR_SOURCE_VOLTAGES);
} else {
clear_error_source(ERROR_SOURCE_VOLTAGES);
}
mcuDelay(10);
return 0;
}
uint8_t AMS_Warning_Loop() {
amsWakeUp();
amsConfigOverUnderVoltage(amsov, amsuv);
amsClearAux();
amsCellMeasurement(&module);
amsAuxAndStatusMeasurement(&module);
amsCheckUnderOverVoltage(&module);
if (!(module.overVoltage | module.underVoltage)) {
currentAMSState = AMSIDLE;
// amsClearWarning();
}
amsStopBalancing();
return 0;
}
uint8_t AMS_Error_Loop() { return 0; }
uint8_t AMS_Charging_Loop() { return 0; }
uint8_t AMS_Discharging_Loop() { return 0; }
uint8_t AMS_Balancing_Loop() {
uint8_t balancingdone = 1;
if ((eepromconfigured == 1) && (internalbalancingalgo == 1) &&
(module.internalDieTemp <
28000 /*Thermal Protection 93°C*/)) // If the EEPROM is configured and
// the internal Balancing Algorithm
// should be used
{
uint16_t highestcellvoltage = module.cellVoltages[0];
uint16_t lowestcellvoltage = module.cellVoltages[0];
uint8_t highestcell = 0;
uint8_t lowestcell = 0;
for (uint8_t n = 0; n < numberofCells; n++) {
if (module.cellVoltages[n] > highestcellvoltage) {
highestcellvoltage = module.cellVoltages[n];
highestcell = n;
}
if (module.cellVoltages[n] < lowestcellvoltage) {
lowestcellvoltage = module.cellVoltages[n];
lowestcell = n;
}
}
if (currentAMSState ==
AMSCHARGING) // Balancing is only Active if the BMS is in Charging Mode
{
uint32_t channelstobalance = 0;
if (highestcellvoltage > startbalancingthreshold) {
for (uint8_t n = 0; n < numberofCells; n++) {
if (module.cellVoltages[n] > stopbalancingthreshold) {
uint16_t dv = module.cellVoltages[n] - lowestcellvoltage;
if (dv > (balancingvoltagedelta * 1000)) {
balancingdone = 0;
channelstobalance |= 1 << n;
}
}
}
}
amsConfigBalancing(channelstobalance, 0x0F);
amsStartBalancing(100);
}
else if (currentAMSState == AMSIDLEBALANCING) {
uint32_t channelstobalance = 0;
if (lowestcellvoltage <
stopbalancingthreshold) // If under Voltage of one Cell is reached
{
amsStopBalancing();
balancingdone = 1;
} else // otherwise continue with regular Balancing Algorithm
{
for (uint8_t n = 0; n < numberofCells; n++) {
uint16_t dv = module.cellVoltages[n] - lowestcellvoltage;
if (dv > balancingvoltagedelta) {
balancingdone = 0;
channelstobalance |= 1 << n;
}
}
amsConfigBalancing(channelstobalance, 0x0F);
amsStartBalancing(100);
}
}
} else {
amsStopBalancing();
balancingdone = 1;
}
return balancingdone;
}
uint8_t writeWarningLog(uint8_t warningCode) {
// eepromWriteWarningLog(warningCode);
return 0;
}
uint8_t writeErrorLog(uint8_t errorCode) {
// eepromWriteErrorLog(errorCode);
return 0;
}
uint8_t integrateCurrent() {
lastticks = currenttick;
currenttick = HAL_GetTick();
if (currenttick < lastticks) {
currentintegrator += (module.auxVoltages[0] - module.auxVoltages[2]) *
(currenttick - lastticks);
}
return 0;
}

View File

@ -1,63 +0,0 @@
#include "PWM_control.h"
#include "stm32f3xx_hal.h"
#include <stdint.h>
uint8_t battery_cooling_status;
//uint32_t powerground1_CCR, powerground2_CCR, battery_cooling_CCR;
TIM_HandleTypeDef* powerground, *battery_cooling;
/*
Pulse width modulation mode allows for generating a signal with a frequency determined by
the value of the TIMx_ARR register and a duty cycle determined by the value of the TIMx_CCRx register.
*/
void PWM_control_init(TIM_HandleTypeDef* pg, TIM_HandleTypeDef* bat_cool){
powerground_status = 0;
battery_cooling_status = 0;
powerground = pg;
battery_cooling = bat_cool;
HAL_TIM_PWM_Start(pg, TIM_CHANNEL_1); //TIM15CH1
HAL_TIM_PWM_Start(pg, TIM_CHANNEL_2); //TIM15CH2
HAL_TIM_PWM_Start(bat_cool, TIM_CHANNEL_3); //TIM1CH3
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_1, 0);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_2, 0);
//PWM_powerground_control(0);
//__HAL_TIM_SET_COMPARE(battery_cooling, TIM_CHANNEL_3, 2000);
}
/*
controls the duty cycle of the fans by setting the CCR of the channel percent/100 = x/ARR
DUTYCYCLE = 40000 * X/100
*/
void PWM_powerground_control(uint8_t percent){
if (percent > 100) //something went wrong
return;
powerground_status = percent;
int ccr = 2000 + ((2000) * (percent/100.0));
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_1, ccr);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_2, ccr);
//TIM15->CCR1 = (TIM15->ARR*POWERGROUND_MAX_DUTY_CYCLE-TIM15->ARR*POWERGROUND_MIN_DUTY_CYCLE) * (percent/100.0) + TIM15->ARR*POWERGROUND_MIN_DUTY_CYCLE;
}
void PWM_set_throttle(){
uint32_t timestamp = HAL_GetTick() + 5000;
while (timestamp > HAL_GetTick()) {}
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_1, 4000);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_2, 4000);
timestamp = HAL_GetTick() + 2000;
while (timestamp > HAL_GetTick()) {}
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_1, 2000);
__HAL_TIM_SET_COMPARE(powerground, TIM_CHANNEL_2, 2000);
timestamp = HAL_GetTick() + 1000;
while (timestamp > HAL_GetTick()) {}
}
void PWM_battery_cooling_control(uint8_t percent){}

View File

@ -1,77 +0,0 @@
#include "TMP1075.h"
#define MAX_TEMP ((int16_t)(59 / 0.0625f))
#define MAX_FAILED_TEMP 12 //TODO: change value for compliance with the actual number of sensors
#warning "change value for compliance with the actual number of sensors"
int16_t tmp1075_temps[N_TEMP_SENSORS] = {0};
uint32_t tmp1075_failed_sensors = 0;
uint8_t nfailed_temp_sensors = 0;
I2C_HandleTypeDef* hi2c;
HAL_StatusTypeDef tmp1075_init(I2C_HandleTypeDef* handle) {
hi2c = handle;
for (int i = 0; i < N_TEMP_SENSORS; i++) {
HAL_StatusTypeDef status = tmp1075_sensor_init(i);
if (status != HAL_OK) {
return status;
}
}
return HAL_OK;
}
void handle_over_maxtemp(uint8_t index, uint16_t value) {
set_error_source(ERROR_SOURCE_TEMPERATURES);
error_data.data_kind = SEK_OVERTEMP;
error_data.data[0] = index;
uint8_t* ptr = &error_data.data[1];
ptr = ftcan_marshal_unsigned(ptr, value, 2);
}
HAL_StatusTypeDef tmp1075_measure() {
int err = 0;
int temp_error = 0;
for (int i = 0; i < N_TEMP_SENSORS; i++) {
if (tmp1075_sensor_read(i, &tmp1075_temps[i]) != HAL_OK ||
(tmp1075_temps[i] & 0x000F) != 0) {
tmp1075_failed_sensors |= 1 << i;
nfailed_temp_sensors++;
err = 1;
} else {
tmp1075_temps[i] >>= 4;
tmp1075_failed_sensors &= ~(1 << i);
if (tmp1075_temps[i] >= MAX_TEMP) {
temp_error = 1;
handle_over_maxtemp(i, tmp1075_temps[i]);
}
#warning "check for under temp"
}
}
if (nfailed_temp_sensors > MAX_FAILED_TEMP) {
error_data.data_kind = SEK_TOO_FEW_TEMPS;
set_error_source(ERROR_SOURCE_TEMPERATURES);
} else if (!temp_error) {
clear_error_source(ERROR_SOURCE_TEMPERATURES);
}
nfailed_temp_sensors = 0;
return err ? HAL_ERROR : HAL_OK;
}
HAL_StatusTypeDef tmp1075_sensor_init(int n) {
uint16_t addr = (0b1000000 | n) << 1;
uint8_t data[] = {0};
return HAL_I2C_Master_Transmit(hi2c, addr, data, sizeof(data), 100);
}
HAL_StatusTypeDef tmp1075_sensor_read(int n, int16_t* res) {
uint16_t addr = (0b1000000 | n) << 1;
addr |= 1; // Read
uint8_t result[2];
HAL_StatusTypeDef status =
HAL_I2C_Master_Receive(hi2c, addr, result, sizeof(result), 5); //5ms timeout for failure (cascading faliure max = 30 * 5 = 150ms)
if (status == HAL_OK) {
*res = (result[0] << 8) | result[1];
}
return status;
}

View File

@ -1,150 +0,0 @@
/*
* can.c
* Created on: Mai 23, 2024
* Author: Hamza
*/
#include "can.h"
//#define CAN_ID_IN 0x501
//#define CAN_ID_OUT 0x502
int can_delay_manager = 0;
void can_init(CAN_HandleTypeDef* hcan) {
ftcan_init(hcan);
ftcan_add_filter(CAN_ID_IN, 0xFFF);
}
/*
This function sends the status of the mvbms, the battery and of powerground.
once every 1s in states: INACTIVE, PRECHARGE, DISCHARGE, CHARGING, ERROR.
once every 0.5s in states: READY, ACTIVE.
with format of:
CAN Messages:
Error bit
MVBMS state
Powerground Status 0-100%
Errors
Battery state of charge
Pack Voltage
Current
Battery temperature (12 bit)
Min/Max. Cell Temp (ID, Min Temp, ID, Max Temp)(3B),
Min/Max Cell Voltage (ID, Min Voltage, ID, Max Voltage)(3B)
bit 0 (1b): empty
bit 1-3 (3b): state
bit 4-11 (8b): powerground status
bit 12-19 (8b): error
bit 20-27 (8b): state of charge from 0-100%
bit 28-39 (12b): battery voltage
bit 40-51 (12b): current measurement
bit 52-63 (12b): temperature of the cell with highest temperature
bit 0-3 (4b): ID of the sensor with highest temperature
bit 4-7 (4b): ID of the sensor with lowest temperataure
bit 8-19 (12b): temperature of the coldest cell
bit 20-23 (4b): ID of the cell with the lowest voltage
bit 24-35 (12b): lowest cell voltage
bit 36-39 (4b): ID of the cell the the highest voltage
bit 40-51 (12b): highest cell voltage
bit 52-63 (12b): empty
*/
void can_handle_send_status() {
if (can_delay_manager > HAL_GetTick())
return;
else
can_delay_manager = HAL_GetTick() + CAN_STATUS_FREQ;
uint8_t data[8] = {};
int8_t id_highest_temp = -1;
int16_t highest_temp = INT16_MIN;
sm_check_battery_temperature(&id_highest_temp, &highest_temp);
data[0] = ((state.current_state << 4) | (powerground_status >> 4)); // 1 bit emptyy | 3 bit state | 4 bit powerground
data[1] = ((powerground_status << 4) | (state.error_source >> 4)); // 4 bit powerground | 4 bit error
data[2] = ((state.error_source << 4) | (0)); // 4 bit error | 4 bit state of charge
data[3] = ((0) + (RELAY_BAT_SIDE_VOLTAGE >> 12)); // 4 bit state of charge | 4 bit battery voltage
data[4] = ((RELAY_BAT_SIDE_VOLTAGE >> 4));
data[5] = ((CURRENT_MEASUREMENT >> 8));
data[6] = ((CURRENT_MEASUREMENT & 0x00F0) | (highest_temp >> 12));
data[7] = ((highest_temp) >> 4);
ftcan_transmit(CAN_ID_OUT, data, sizeof(data));
int8_t id_lowest_temp = -1;
int16_t lowest_temp = INT16_MIN;
for (int i = 0; i < N_TEMP_SENSORS; i++) {
if (tmp1075_temps[i] < lowest_temp){
id_lowest_temp = i;
lowest_temp = tmp1075_temps[i];
}
}
int8_t id_lowest_volt = -1;
int16_t lowest_volt = INT16_MIN;
int8_t id_highest_volt = -1;
int16_t highest_volt = INT16_MIN;
for (int i = 0; i < module.sumOfCellMeasurements; i++) {
if (sm_return_cell_voltage(i) < lowest_temp){
id_lowest_volt = i;
lowest_volt = sm_return_cell_voltage(i);
}
if (sm_return_cell_voltage(i) > highest_temp){
id_highest_volt = i;
highest_volt = sm_return_cell_voltage(i);
}
}
data[0] = ((id_highest_temp & 0x0F) << 4 | (id_lowest_temp & 0x0F));
data[1] = ((lowest_temp) >> 8);
data[2] = ((lowest_temp & 0x00F0) | (id_lowest_volt & 0x0F));
data[3] = (lowest_volt >> 8);
data[4] = ((lowest_volt & 0x00F0) | (id_highest_volt & 0x0F));
data[5] = ((highest_volt >> 8));
data[6] = ((highest_volt & 0x00F0));
data[7] = 0;
ftcan_transmit(CAN_ID_OUT, data, sizeof(data));
}
/*
can_handle_recieve_command() should only check if the message is valid and then hand it
to the sm_handle_ams_in() which handles the state machine transition.
This function recieves a command from the Autobox with the CAN ID of 0x501.
with format of:
data[0] = target state
0x0 STATE_INACTIVE | disconnect power to the ESC of powerground. Send it to return the mvbms to idle/monitoring mode. If data[1] != 0 -> assume bad CAN message.
0x1 STATE_READY | conneect power to the ESC of powerground and but with no PWM signal. If data[1] != 0 -> assume bad CAN message.
0x2 STATE_ACTIVE | activate powerground at (data[1]) percent. If data[1] > 100 -> assume bad CAN message.
allowed transitions:
STATE_INACTIVE -> STATE_READY
STATE_READY -> STATE_INACTIVE, STATE_ACTIVE
STATE_ACTIVE -> STATE_INACTIVE, STATE_READY
*/
void can_handle_recieve_command(const uint8_t *data){
if (data[0] == 0x00 && data[1] == 0x00){
sm_handle_ams_in(data);
} else if (data[0] == 0x01 && data[1] == 0x00){
sm_handle_ams_in(data);
} else if (data[0] == 0x02 && data[1] <= 100) {
sm_handle_ams_in(data);
}
}
/*
implements the _weak method ftcan_msg_recieved_cb() which throws an interrupt when a CAN message is recieved.
it only checks if the id is and datalen is correct thans hands data over to can_handle_recieve_command().
in MXCUBE under CAN NVIC settings "USB low priority or CAN_RX0 interrupts" has to be on
*/
void ftcan_msg_received_cb(uint16_t id, size_t datalen, const uint8_t *data){
if (id == 0x501 && datalen == 2){
can_handle_recieve_command(data);
}
}

View File

@ -1,13 +0,0 @@
#include "errors.h"
#include "stm32f3xx_hal.h"
SlaveErrorData error_data;
void set_error_source(int source) {
if (!error_data.error_sources) {
error_data.errors_since = HAL_GetTick();
}
error_data.error_sources |= source;
}
void clear_error_source(int source) { error_data.error_sources &= ~source; }

View File

@ -21,17 +21,7 @@
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "ADBMS_Abstraction.h"
#include "ADBMS_CMD_MAKROS.h"
#include "PWM_control.h"
#include "can.h"
#include "AMS_HighLevel.h"
#include "state_machine.h"
#include "TMP1075.h"
#include "errors.h"
#include "stm32f302xc.h"
#include "stm32f3xx_hal.h"
#include "stm32f3xx_hal_tim.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
@ -119,12 +109,7 @@ int main(void)
MX_USART1_UART_Init();
MX_TIM1_Init();
/* USER CODE BEGIN 2 */
sm_init();
tmp1075_init(&hi2c1);
AMS_Init(&hspi1);
can_init(&hcan);
PWM_control_init(&htim15, &htim1);
HAL_Delay(10);
/* USER CODE END 2 */
/* Infinite loop */
@ -134,10 +119,6 @@ int main(void)
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
AMS_Loop();
sm_update();
//sm_test_cycle_states();
can_handle_send_status();
}
/* USER CODE END 3 */
}
@ -155,11 +136,12 @@ void SystemClock_Config(void)
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL4;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
@ -169,7 +151,7 @@ void SystemClock_Config(void)
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSE;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
@ -205,15 +187,15 @@ static void MX_CAN_Init(void)
/* USER CODE END CAN_Init 1 */
hcan.Instance = CAN;
hcan.Init.Prescaler = 2;
hcan.Init.Prescaler = 16;
hcan.Init.Mode = CAN_MODE_NORMAL;
hcan.Init.SyncJumpWidth = CAN_SJW_1TQ;
hcan.Init.TimeSeg1 = CAN_BS1_13TQ;
hcan.Init.TimeSeg2 = CAN_BS2_2TQ;
hcan.Init.TimeSeg1 = CAN_BS1_1TQ;
hcan.Init.TimeSeg2 = CAN_BS2_1TQ;
hcan.Init.TimeTriggeredMode = DISABLE;
hcan.Init.AutoBusOff = ENABLE;
hcan.Init.AutoBusOff = DISABLE;
hcan.Init.AutoWakeUp = DISABLE;
hcan.Init.AutoRetransmission = ENABLE;
hcan.Init.AutoRetransmission = DISABLE;
hcan.Init.ReceiveFifoLocked = DISABLE;
hcan.Init.TransmitFifoPriority = DISABLE;
if (HAL_CAN_Init(&hcan) != HAL_OK)
@ -404,9 +386,9 @@ static void MX_TIM15_Init(void)
/* USER CODE END TIM15_Init 1 */
htim15.Instance = TIM15;
htim15.Init.Prescaler = 7;
htim15.Init.Prescaler = 0;
htim15.Init.CounterMode = TIM_COUNTERMODE_UP;
htim15.Init.Period = 39999;
htim15.Init.Period = 65535;
htim15.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim15.Init.RepetitionCounter = 0;
htim15.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
@ -513,7 +495,7 @@ static void MX_GPIO_Init(void)
HAL_GPIO_WritePin(GPIOB, STATUS_LED_R_Pin|STATUS_LED_B_Pin|STATUS_LED_G_Pin, GPIO_PIN_SET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(PRECHARGE_EN_GPIO_Port, PRECHARGE_EN_Pin, GPIO_PIN_RESET);
HAL_GPIO_WritePin(GPIOB, PRECHARGE_EN_Pin|AUX_IN_Pin, GPIO_PIN_RESET);
/*Configure GPIO pins : PC13 PC14 PC15 */
GPIO_InitStruct.Pin = GPIO_PIN_13|GPIO_PIN_14|GPIO_PIN_15;
@ -528,21 +510,29 @@ static void MX_GPIO_Init(void)
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/*Configure GPIO pins : STATUS_LED_R_Pin STATUS_LED_B_Pin STATUS_LED_G_Pin PRECHARGE_EN_Pin */
GPIO_InitStruct.Pin = STATUS_LED_R_Pin|STATUS_LED_B_Pin|STATUS_LED_G_Pin|PRECHARGE_EN_Pin;
/*Configure GPIO pins : STATUS_LED_R_Pin STATUS_LED_B_Pin STATUS_LED_G_Pin PRECHARGE_EN_Pin
AUX_IN_Pin */
GPIO_InitStruct.Pin = STATUS_LED_R_Pin|STATUS_LED_B_Pin|STATUS_LED_G_Pin|PRECHARGE_EN_Pin
|AUX_IN_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);
/*Configure GPIO pins : PB10 PB12 PB13 PB14
PB4 PB5 PB8 */
GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_12|GPIO_PIN_13|GPIO_PIN_14
|GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_8;
/*Configure GPIO pins : PB10 PB12 PB4 PB5
PB8 */
GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_12|GPIO_PIN_4|GPIO_PIN_5
|GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/*Configure GPIO pin : AUX_OUT_Pin */
GPIO_InitStruct.Pin = AUX_OUT_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(AUX_OUT_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : RELAY_BATT_SIDE_ON_Pin RELAY_ESC_SIDE_ON_Pin CURRENT_SENSOR_ON_Pin */
GPIO_InitStruct.Pin = RELAY_BATT_SIDE_ON_Pin|RELAY_ESC_SIDE_ON_Pin|CURRENT_SENSOR_ON_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;

View File

@ -1,325 +0,0 @@
#include "state_machine.h"
#include "AMS_HighLevel.h"
#include "TMP1075.h"
#include "errors.h"
#include "stm32f3xx_hal.h"
#include <stdint.h>
#include <stdio.h>
StateHandle state;
int16_t RELAY_BAT_SIDE_VOLTAGE;
int16_t RELAY_ESC_SIDE_VOLTAGE;
int16_t CURRENT_MEASUREMENT;
uint8_t powerground_status;
uint32_t timestamp;
void sm_init(){
state.current_state = STATE_INACTIVE;
state.target_state = STATE_INACTIVE;
state.error_source = 0;
}
void sm_update(){
sm_check_errors();
RELAY_BAT_SIDE_VOLTAGE = module.auxVoltages[0] * 12.42; // the calculation says the factor is 11.989. 12.42 yields the better result
RELAY_ESC_SIDE_VOLTAGE = module.auxVoltages[1] * 12.42;
CURRENT_MEASUREMENT = (module.auxVoltages[2] - 2496) * 300;
switch (state.current_state) {
case STATE_INACTIVE:
state.current_state = sm_update_inactive(); // monitor only
break;
case STATE_PRECHARGE:
state.current_state = sm_update_precharge(); // set PRECHARGE and turn on cooling at 50% or such
break;
case STATE_READY:
state.current_state = sm_update_ready(); // keep cooling at 50%, get ready to turn on powerground
break;
case STATE_ACTIVE:
state.current_state = sm_update_active(); // set PRECHARGE and turn on cooling at 50% or such
break;
case STATE_DISCHARGE:
state.current_state = sm_update_discharge(); // open the main relay, keep PRECHARGE closed
break;
case STATE_CHARGING_PRECHARGE:
state.current_state = sm_update_charging_precharge();
break;
case STATE_CHARGING:
state.current_state = sm_update_charging(); // monitor and turn on cooling if needed.
break;
case STATE_ERROR:
state.current_state = sm_update_error(); // enter the correct ERROR state
break;
}
sm_set_relay_positions(state.current_state);
state.target_state = state.current_state;
}
State sm_update_inactive(){
switch (state.target_state) {
case STATE_PRECHARGE:
return STATE_PRECHARGE;
case STATE_CHARGING_PRECHARGE:
return STATE_CHARGING_PRECHARGE;
default:
return STATE_INACTIVE;
}
}
State sm_update_precharge(){
switch (state.target_state) {
case STATE_INACTIVE: // if CAN Signal 0000 0000 then immidiete shutdown
return STATE_DISCHARGE;
case STATE_PRECHARGE:
if (RELAY_BAT_SIDE_VOLTAGE-RELAY_ESC_SIDE_VOLTAGE < 100){
PWM_set_throttle();
return STATE_READY;
}
break;
case STATE_DISCHARGE:
return STATE_DISCHARGE;
default:
return STATE_PRECHARGE;
}
}
State sm_update_ready(){
switch (state.target_state) {
case STATE_ACTIVE: // if CAN Signal 1100 0000 then turn on powerground
return STATE_ACTIVE;
case STATE_DISCHARGE: // if CAN Signal 0000 0000 then shutdown
return STATE_DISCHARGE;
default:
return STATE_READY;
}
}
State sm_update_active(){
switch (state.target_state) {
case STATE_READY: // if CAN Signal 1000 0000 then turn oof powerground but stay ready
return STATE_READY;
case STATE_DISCHARGE: // if CAN Signal 0000 0000 then shutdown
return STATE_DISCHARGE;
default:
return STATE_ACTIVE;
}
}
State sm_update_discharge(){
switch (state.target_state) {
case STATE_DISCHARGE:
if (RELAY_ESC_SIDE_VOLTAGE < 5000)
return STATE_INACTIVE;
case STATE_PRECHARGE: // if CAN Signal 1000 0000 then get ready
return STATE_PRECHARGE;
default:
return STATE_DISCHARGE;
}
}
State sm_update_charging_precharge(){
switch (state.target_state) {
case STATE_CHARGING:
return STATE_CHARGING;
case STATE_DISCHARGE:
return STATE_DISCHARGE;
default:
return STATE_CHARGING_PRECHARGE;
}
}
State sm_update_charging(){
switch (state.target_state) {
case STATE_DISCHARGE:
return STATE_DISCHARGE;
default:
return STATE_CHARGING;
}
}
State sm_update_error(){
switch (state.target_state) {
case STATE_DISCHARGE:
return STATE_DISCHARGE;
default:
return STATE_ERROR;
}
}
void sm_set_relay_positions(State current_state){
switch (state.current_state) {
case STATE_INACTIVE:
sm_set_relay(RELAY_MAIN, 0);
sm_set_relay(RELAY_PRECHARGE, 0);
break;
case STATE_PRECHARGE:
sm_set_relay(RELAY_MAIN, 0);
sm_set_relay(RELAY_PRECHARGE, 1);
break;
case STATE_READY:
sm_set_relay(RELAY_MAIN, 1);
sm_set_relay(RELAY_PRECHARGE, 0);
break;
case STATE_ACTIVE:
sm_set_relay(RELAY_MAIN, 1);
sm_set_relay(RELAY_PRECHARGE, 0);
break;
case STATE_DISCHARGE:
sm_set_relay(RELAY_MAIN, 0);
sm_set_relay(RELAY_PRECHARGE, 0);
break;
case STATE_CHARGING_PRECHARGE:
sm_set_relay(RELAY_MAIN, 0);
sm_set_relay(RELAY_PRECHARGE, 1);
break;
case STATE_CHARGING:
sm_set_relay(RELAY_MAIN, 1);
sm_set_relay(RELAY_PRECHARGE, 0);
break;
case STATE_ERROR:
sm_set_relay(RELAY_MAIN, 0);
sm_set_relay(RELAY_PRECHARGE, 0);
break;
}
}
void sm_set_relay(Relay relay, bool closed){
GPIO_PinState state = closed ? GPIO_PIN_SET : GPIO_PIN_RESET;
switch (relay) {
case RELAY_MAIN:
HAL_GPIO_WritePin(RELAY_EN_GPIO_Port, RELAY_EN_Pin, state);
relay_closed = closed;
break;
case RELAY_PRECHARGE:
HAL_GPIO_WritePin(PRECHARGE_EN_GPIO_Port, PRECHARGE_EN_Pin, state);
precharge_closed = closed;
break;
}
}
void sm_check_charging(){
if (RELAY_BAT_SIDE_VOLTAGE < RELAY_ESC_SIDE_VOLTAGE && timestamp == 0)
timestamp = HAL_GetTick() + 5000;
if (timestamp < HAL_GetTick())
state.target_state = STATE_CHARGING_PRECHARGE;
}
/* returns the ID and temperature of the hottest cell */
void sm_check_battery_temperature(int8_t *id, int16_t *temp){
for (int i = 0; i < N_TEMP_SENSORS; i++) {
if (tmp1075_temps[i] > *temp){
*id = i;
*temp = tmp1075_temps[i];
}
}
}
int16_t sm_return_cell_temperature(int id){
return tmp1075_temps[id];
}
int16_t sm_return_cell_voltage(int id){
return module.cellVoltages[id];
}
void sm_handle_ams_in(const uint8_t *data){
switch (data[0]) {
case 0x00:
if (state.current_state != STATE_INACTIVE){
state.target_state = STATE_DISCHARGE;
}
break;
case 0x01:
if (state.target_state == STATE_INACTIVE || state.target_state == STATE_DISCHARGE){
state.target_state = STATE_PRECHARGE;
} else if (state.target_state == STATE_ACTIVE){
state.target_state = STATE_READY;
}
break;
case 0x02:
if (state.current_state == STATE_READY || state.current_state == STATE_ACTIVE){
PWM_powerground_control(data[1]);
state.target_state = STATE_ACTIVE; // READY -> ACTIVE
}
break;
}
}
void sm_set_error(ErrorKind error_kind, bool is_errored){}
#warning TODO: add error checking for everything here
void sm_check_errors(){
switch (error_data.data_kind) {
case SEK_OVERTEMP:
case SEK_UNDERTEMP:
case SEK_TOO_FEW_TEMPS:
state.error_type.temperature_error = 1;
case SEK_OVERVOLT:
case SEK_UNDERVOLT:
case SEK_OPENWIRE:
case SEK_EEPROM_ERR:
case SEK_INTERNAL_BMS_TIMEOUT:
state.error_type.bms_timeout = 1;
case SEK_INTERNAL_BMS_CHECKSUM_FAIL:
case SEK_INTERNAL_BMS_OVERTEMP:
case SEK_INTERNAL_BMS_FAULT:
state.error_type.bms_fault = 1;
break;
}
if (1){
state.error_type.current_error = 1;
}
if (1){
state.error_type.current_sensor_missing = 1;
}
if (RELAY_BAT_SIDE_VOLTAGE < 30000){
state.error_type.voltage_error = 1;
}
if (1){
state.error_type.voltage_missing = 1;
}
}
void sm_test_cycle_states(){
RELAY_BAT_SIDE_VOLTAGE = module.auxVoltages[0];
RELAY_ESC_SIDE_VOLTAGE = module.auxVoltages[1];
CURRENT_MEASUREMENT = module.auxVoltages[2];
sm_set_relay_positions(state.current_state);
if (timestamp > HAL_GetTick())
return;
switch (state.current_state) {
case STATE_INACTIVE:
state.current_state = STATE_PRECHARGE;
timestamp = HAL_GetTick() + 30000;
PWM_powerground_control(0);
break;
case STATE_PRECHARGE:
state.current_state = STATE_READY;
timestamp = HAL_GetTick() + 10000;
break;
case STATE_READY:
state.current_state = STATE_ACTIVE;
timestamp = HAL_GetTick() + 10000;
break;
case STATE_ACTIVE:
state.current_state = STATE_DISCHARGE;
timestamp = HAL_GetTick() + 10000;
PWM_powerground_control(1);
break;
case STATE_DISCHARGE:
state.current_state = STATE_INACTIVE;
timestamp = HAL_GetTick() + 10000;
break;
}
state.target_state = state.current_state;
}

View File

@ -108,11 +108,6 @@ void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan)
GPIO_InitStruct.Alternate = GPIO_AF9_CAN;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* CAN interrupt Init */
HAL_NVIC_SetPriority(USB_LP_CAN_RX0_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(USB_LP_CAN_RX0_IRQn);
HAL_NVIC_SetPriority(CAN_RX1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(CAN_RX1_IRQn);
/* USER CODE BEGIN CAN_MspInit 1 */
/* USER CODE END CAN_MspInit 1 */
@ -142,9 +137,6 @@ void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan)
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* CAN interrupt DeInit */
HAL_NVIC_DisableIRQ(USB_LP_CAN_RX0_IRQn);
HAL_NVIC_DisableIRQ(CAN_RX1_IRQn);
/* USER CODE BEGIN CAN_MspDeInit 1 */
/* USER CODE END CAN_MspDeInit 1 */
@ -339,12 +331,12 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
/**TIM1 GPIO Configuration
PB15 ------> TIM1_CH3N
*/
GPIO_InitStruct.Pin = PWM_Battery_Cooling_Pin;
GPIO_InitStruct.Pin = GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF4_TIM1;
HAL_GPIO_Init(PWM_Battery_Cooling_GPIO_Port, &GPIO_InitStruct);
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN TIM1_MspPostInit 1 */

View File

@ -55,7 +55,7 @@
/* USER CODE END 0 */
/* External variables --------------------------------------------------------*/
extern CAN_HandleTypeDef hcan;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
@ -198,34 +198,6 @@ void SysTick_Handler(void)
/* please refer to the startup file (startup_stm32f3xx.s). */
/******************************************************************************/
/**
* @brief This function handles USB low priority or CAN_RX0 interrupts.
*/
void USB_LP_CAN_RX0_IRQHandler(void)
{
/* USER CODE BEGIN USB_LP_CAN_RX0_IRQn 0 */
/* USER CODE END USB_LP_CAN_RX0_IRQn 0 */
HAL_CAN_IRQHandler(&hcan);
/* USER CODE BEGIN USB_LP_CAN_RX0_IRQn 1 */
/* USER CODE END USB_LP_CAN_RX0_IRQn 1 */
}
/**
* @brief This function handles CAN RX1 interrupt.
*/
void CAN_RX1_IRQHandler(void)
{
/* USER CODE BEGIN CAN_RX1_IRQn 0 */
/* USER CODE END CAN_RX1_IRQn 0 */
HAL_CAN_IRQHandler(&hcan);
/* USER CODE BEGIN CAN_RX1_IRQn 1 */
/* USER CODE END CAN_RX1_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

View File

@ -1,176 +0,0 @@
/**
******************************************************************************
* @file syscalls.c
* @author Auto-generated by STM32CubeMX
* @brief Minimal System calls file
*
* For more information about which c-functions
* need which of these lowlevel functions
* please consult the Newlib libc-manual
******************************************************************************
* @attention
*
* Copyright (c) 2020-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.
*
******************************************************************************
*/
/* Includes */
#include <sys/stat.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <signal.h>
#include <time.h>
#include <sys/time.h>
#include <sys/times.h>
/* Variables */
extern int __io_putchar(int ch) __attribute__((weak));
extern int __io_getchar(void) __attribute__((weak));
char *__env[1] = { 0 };
char **environ = __env;
/* Functions */
void initialise_monitor_handles()
{
}
int _getpid(void)
{
return 1;
}
int _kill(int pid, int sig)
{
(void)pid;
(void)sig;
errno = EINVAL;
return -1;
}
void _exit (int status)
{
_kill(status, -1);
while (1) {} /* Make sure we hang here */
}
__attribute__((weak)) int _read(int file, char *ptr, int len)
{
(void)file;
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
*ptr++ = __io_getchar();
}
return len;
}
__attribute__((weak)) int _write(int file, char *ptr, int len)
{
(void)file;
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
__io_putchar(*ptr++);
}
return len;
}
int _close(int file)
{
(void)file;
return -1;
}
int _fstat(int file, struct stat *st)
{
(void)file;
st->st_mode = S_IFCHR;
return 0;
}
int _isatty(int file)
{
(void)file;
return 1;
}
int _lseek(int file, int ptr, int dir)
{
(void)file;
(void)ptr;
(void)dir;
return 0;
}
int _open(char *path, int flags, ...)
{
(void)path;
(void)flags;
/* Pretend like we always fail */
return -1;
}
int _wait(int *status)
{
(void)status;
errno = ECHILD;
return -1;
}
int _unlink(char *name)
{
(void)name;
errno = ENOENT;
return -1;
}
int _times(struct tms *buf)
{
(void)buf;
return -1;
}
int _stat(char *file, struct stat *st)
{
(void)file;
st->st_mode = S_IFCHR;
return 0;
}
int _link(char *old, char *new)
{
(void)old;
(void)new;
errno = EMLINK;
return -1;
}
int _fork(void)
{
errno = EAGAIN;
return -1;
}
int _execve(char *name, char **argv, char **env)
{
(void)name;
(void)argv;
(void)env;
errno = ENOMEM;
return -1;
}

View File

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

View File

@ -1,5 +1,5 @@
##########################################################################################################################
# File automatically-generated by tool: [projectgenerator] version: [4.3.0-B58] date: [Mon Jun 03 16:11:34 EEST 2024]
# File automatically-generated by tool: [projectgenerator] version: [4.3.0-B58] date: [Tue Jul 09 13:45:39 EEST 2024]
##########################################################################################################################
# ------------------------------------------------
@ -13,7 +13,7 @@
######################################
# target
######################################
TARGET = mvbms
TARGET = mvbms-test-24
######################################

View File

@ -1,266 +1,266 @@
#MicroXplorer Configuration settings - do not modify
CAD.formats=
CAD.pinconfig=
CAD.provider=
CAN.CalculateBaudRate=333333
CAN.CalculateTimeBit=3000
CAN.CalculateTimeQuantum=1000.0
CAN.IPParameters=CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate
File.Version=6
GPIO.groupedBy=Group By Peripherals
KeepUserPlacement=true
Mcu.CPN=STM32F302CBT6
Mcu.Family=STM32F3
Mcu.IP0=CAN
Mcu.IP1=I2C1
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI1
Mcu.IP5=SYS
Mcu.IP6=TIM1
Mcu.IP7=TIM15
Mcu.IP8=USART1
Mcu.IPNb=9
Mcu.Name=STM32F302C(B-C)Tx
Mcu.Package=LQFP48
Mcu.Pin0=PF0-OSC_IN
Mcu.Pin1=PF1-OSC_OUT
Mcu.Pin10=PB0
Mcu.Pin11=PB1
Mcu.Pin12=PB2
Mcu.Pin13=PB11
Mcu.Pin14=PB13
Mcu.Pin15=PB14
Mcu.Pin16=PB15
Mcu.Pin17=PA8
Mcu.Pin18=PA9
Mcu.Pin19=PA10
Mcu.Pin2=PA0
Mcu.Pin20=PA11
Mcu.Pin21=PA12
Mcu.Pin22=PA13
Mcu.Pin23=PA14
Mcu.Pin24=PA15
Mcu.Pin25=PB3
Mcu.Pin26=PB6
Mcu.Pin27=PB7
Mcu.Pin28=PB9
Mcu.Pin29=VP_SYS_VS_Systick
Mcu.Pin3=PA1
Mcu.Pin4=PA2
Mcu.Pin5=PA3
Mcu.Pin6=PA4
Mcu.Pin7=PA5
Mcu.Pin8=PA6
Mcu.Pin9=PA7
Mcu.PinsNb=30
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F302CBTx
MxCube.Version=6.11.1
MxDb.Version=DB.6.0.111
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
PA0.GPIOParameters=PinState,GPIO_Label
PA0.GPIO_Label=RELAY_EN
PA0.Locked=true
PA0.PinState=GPIO_PIN_RESET
PA0.Signal=GPIO_Output
PA1.GPIOParameters=PinState,GPIO_Label
PA1.GPIO_Label=_60V_EN
PA1.Locked=true
PA1.PinState=GPIO_PIN_RESET
PA1.Signal=GPIO_Output
PA10.GPIOParameters=GPIO_Label
PA10.GPIO_Label=CURRENT_SENSOR_ON
PA10.Locked=true
PA10.Signal=GPIO_Input
PA11.Locked=true
PA11.Mode=CAN_Activate
PA11.Signal=CAN_RX
PA12.Locked=true
PA12.Mode=CAN_Activate
PA12.Signal=CAN_TX
PA13.Locked=true
PA13.Mode=Trace_Asynchronous_SW
PA13.Signal=SYS_JTMS-SWDIO
PA14.Locked=true
PA14.Mode=Trace_Asynchronous_SW
PA14.Signal=SYS_JTCK-SWCLK
PA15.Locked=true
PA15.Mode=I2C
PA15.Signal=I2C1_SCL
PA2.GPIOParameters=GPIO_Label
PA2.GPIO_Label=PWM_PG_FAN1
PA2.Locked=true
PA2.Signal=S_TIM15_CH1
PA3.GPIOParameters=GPIO_Label
PA3.GPIO_Label=PWM_PG_FAN2
PA3.Locked=true
PA3.Signal=S_TIM15_CH2
PA4.GPIOParameters=GPIO_Label
PA4.GPIO_Label=CSB
PA4.Locked=true
PA4.Signal=GPIO_Output
PA5.Locked=true
PA5.Mode=Full_Duplex_Master
PA5.Signal=SPI1_SCK
PA6.Locked=true
PA6.Mode=Full_Duplex_Master
PA6.Signal=SPI1_MISO
PA7.Locked=true
PA7.Mode=Full_Duplex_Master
PA7.Signal=SPI1_MOSI
PA8.GPIOParameters=GPIO_Label
PA8.GPIO_Label=RELAY_BATT_SIDE_ON
PA8.Locked=true
PA8.Signal=GPIO_Input
PA9.GPIOParameters=GPIO_Label
PA9.GPIO_Label=RELAY_ESC_SIDE_ON
PA9.Locked=true
PA9.Signal=GPIO_Input
PB0.GPIOParameters=PinState,GPIO_Label
PB0.GPIO_Label=STATUS_LED_R
PB0.Locked=true
PB0.PinState=GPIO_PIN_SET
PB0.Signal=GPIO_Output
PB1.GPIOParameters=PinState,GPIO_Label
PB1.GPIO_Label=STATUS_LED_B
PB1.Locked=true
PB1.PinState=GPIO_PIN_SET
PB1.Signal=GPIO_Output
PB11.GPIOParameters=PinState,GPIO_Label
PB11.GPIO_Label=PRECHARGE_EN
PB11.Locked=true
PB11.PinState=GPIO_PIN_RESET
PB11.Signal=GPIO_Output
PB13.GPIOParameters=GPIO_Label
PB13.GPIO_Label=AUX_IN
PB13.Locked=true
PB13.Signal=GPIO_Output
PB14.GPIOParameters=GPIO_Label
PB14.GPIO_Label=AUX_OUT
PB14.Locked=true
PB14.Signal=GPIO_Input
PB15.Locked=true
PB15.Mode=PWM Generation3 CH3N
PB15.Signal=TIM1_CH3N
PB2.GPIOParameters=PinState,GPIO_Label
PB2.GPIO_Label=STATUS_LED_G
PB2.Locked=true
PB2.PinState=GPIO_PIN_SET
PB2.Signal=GPIO_Output
PB3.Locked=true
PB3.Mode=Trace_Asynchronous_SW
PB3.Signal=SYS_JTDO-TRACESWO
PB6.Locked=true
PB6.Mode=Asynchronous
PB6.Signal=USART1_TX
PB7.Locked=true
PB7.Mode=Asynchronous
PB7.Signal=USART1_RX
PB9.Locked=true
PB9.Mode=I2C
PB9.Signal=I2C1_SDA
PF0-OSC_IN.Locked=true
PF0-OSC_IN.Mode=HSE-External-Oscillator
PF0-OSC_IN.Signal=RCC_OSC_IN
PF1-OSC_OUT.Locked=true
PF1-OSC_OUT.Mode=HSE-External-Oscillator
PF1-OSC_OUT.Signal=RCC_OSC_OUT
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
ProjectManager.CoupleFile=false
ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F302CBTx
ProjectManager.FirmwarePackage=STM32Cube FW_F3 V1.11.4
ProjectManager.FreePins=true
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=true
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=mvbms-test-24.ioc
ProjectManager.ProjectName=mvbms-test-24
ProjectManager.ProjectStructure=
ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=Makefile
ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN_Init-CAN-false-HAL-true,4-MX_I2C1_Init-I2C1-false-HAL-true,5-MX_SPI1_Init-SPI1-false-HAL-true,6-MX_TIM15_Init-TIM15-false-HAL-true,7-MX_USART1_UART_Init-USART1-false-HAL-true,8-MX_TIM1_Init-TIM1-false-HAL-true
RCC.ADC12outputFreq_Value=16000000
RCC.AHBFreq_Value=16000000
RCC.APB1Freq_Value=16000000
RCC.APB1TimFreq_Value=16000000
RCC.APB2Freq_Value=16000000
RCC.APB2TimFreq_Value=16000000
RCC.CortexFreq_Value=16000000
RCC.FCLKCortexFreq_Value=16000000
RCC.FamilyName=M
RCC.HCLKFreq_Value=16000000
RCC.HSEPLLFreq_Value=8000000
RCC.HSE_VALUE=8000000
RCC.HSIPLLFreq_Value=4000000
RCC.HSI_VALUE=8000000
RCC.I2C1Freq_Value=8000000
RCC.I2C2Freq_Value=8000000
RCC.IPParameters=ADC12outputFreq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSEPLLFreq_Value,HSE_VALUE,HSIPLLFreq_Value,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,LSE_VALUE,LSI_VALUE,MCOFreq_Value,PLLCLKFreq_Value,PLLMCOFreq_Value,PLLMUL,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSourceVirtual,TIM1Freq_Value,TIM2Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOOutput2Freq_Value
RCC.LSE_VALUE=32768
RCC.LSI_VALUE=40000
RCC.MCOFreq_Value=16000000
RCC.PLLCLKFreq_Value=16000000
RCC.PLLMCOFreq_Value=8000000
RCC.PLLMUL=RCC_PLL_MUL4
RCC.RTCFreq_Value=40000
RCC.RTCHSEDivFreq_Value=250000
RCC.SYSCLKFreq_VALUE=16000000
RCC.SYSCLKSourceVirtual=RCC_SYSCLKSOURCE_PLLCLK
RCC.TIM1Freq_Value=16000000
RCC.TIM2Freq_Value=16000000
RCC.USART1Freq_Value=16000000
RCC.USART2Freq_Value=16000000
RCC.USART3Freq_Value=16000000
RCC.USBFreq_Value=16000000
RCC.VCOOutput2Freq_Value=4000000
SH.S_TIM15_CH1.0=TIM15_CH1,PWM Generation1 CH1
SH.S_TIM15_CH1.ConfNb=1
SH.S_TIM15_CH2.0=TIM15_CH2,PWM Generation2 CH2
SH.S_TIM15_CH2.ConfNb=1
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_32
SPI1.CalculateBaudRate=500.0 KBits/s
SPI1.DataSize=SPI_DATASIZE_8BIT
SPI1.Direction=SPI_DIRECTION_2LINES
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler
SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
TIM1.Channel-PWM\ Generation3\ CH3N=TIM_CHANNEL_3
TIM1.IPParameters=Channel-PWM Generation3 CH3N
TIM15.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM15.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
TIM15.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2
USART1.IPParameters=VirtualMode-Asynchronous
USART1.VirtualMode-Asynchronous=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
board=custom
#MicroXplorer Configuration settings - do not modify
CAD.formats=
CAD.pinconfig=
CAD.provider=
CAN.CalculateBaudRate=333333
CAN.CalculateTimeBit=3000
CAN.CalculateTimeQuantum=1000.0
CAN.IPParameters=CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate
File.Version=6
GPIO.groupedBy=Group By Peripherals
KeepUserPlacement=true
Mcu.CPN=STM32F302CBT6
Mcu.Family=STM32F3
Mcu.IP0=CAN
Mcu.IP1=I2C1
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI1
Mcu.IP5=SYS
Mcu.IP6=TIM1
Mcu.IP7=TIM15
Mcu.IP8=USART1
Mcu.IPNb=9
Mcu.Name=STM32F302C(B-C)Tx
Mcu.Package=LQFP48
Mcu.Pin0=PF0-OSC_IN
Mcu.Pin1=PF1-OSC_OUT
Mcu.Pin10=PB0
Mcu.Pin11=PB1
Mcu.Pin12=PB2
Mcu.Pin13=PB11
Mcu.Pin14=PB13
Mcu.Pin15=PB14
Mcu.Pin16=PB15
Mcu.Pin17=PA8
Mcu.Pin18=PA9
Mcu.Pin19=PA10
Mcu.Pin2=PA0
Mcu.Pin20=PA11
Mcu.Pin21=PA12
Mcu.Pin22=PA13
Mcu.Pin23=PA14
Mcu.Pin24=PA15
Mcu.Pin25=PB3
Mcu.Pin26=PB6
Mcu.Pin27=PB7
Mcu.Pin28=PB9
Mcu.Pin29=VP_SYS_VS_Systick
Mcu.Pin3=PA1
Mcu.Pin4=PA2
Mcu.Pin5=PA3
Mcu.Pin6=PA4
Mcu.Pin7=PA5
Mcu.Pin8=PA6
Mcu.Pin9=PA7
Mcu.PinsNb=30
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F302CBTx
MxCube.Version=6.11.1
MxDb.Version=DB.6.0.111
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
PA0.GPIOParameters=PinState,GPIO_Label
PA0.GPIO_Label=RELAY_EN
PA0.Locked=true
PA0.PinState=GPIO_PIN_RESET
PA0.Signal=GPIO_Output
PA1.GPIOParameters=PinState,GPIO_Label
PA1.GPIO_Label=_60V_EN
PA1.Locked=true
PA1.PinState=GPIO_PIN_RESET
PA1.Signal=GPIO_Output
PA10.GPIOParameters=GPIO_Label
PA10.GPIO_Label=CURRENT_SENSOR_ON
PA10.Locked=true
PA10.Signal=GPIO_Input
PA11.Locked=true
PA11.Mode=CAN_Activate
PA11.Signal=CAN_RX
PA12.Locked=true
PA12.Mode=CAN_Activate
PA12.Signal=CAN_TX
PA13.Locked=true
PA13.Mode=Trace_Asynchronous_SW
PA13.Signal=SYS_JTMS-SWDIO
PA14.Locked=true
PA14.Mode=Trace_Asynchronous_SW
PA14.Signal=SYS_JTCK-SWCLK
PA15.Locked=true
PA15.Mode=I2C
PA15.Signal=I2C1_SCL
PA2.GPIOParameters=GPIO_Label
PA2.GPIO_Label=PWM_PG_FAN1
PA2.Locked=true
PA2.Signal=S_TIM15_CH1
PA3.GPIOParameters=GPIO_Label
PA3.GPIO_Label=PWM_PG_FAN2
PA3.Locked=true
PA3.Signal=S_TIM15_CH2
PA4.GPIOParameters=GPIO_Label
PA4.GPIO_Label=CSB
PA4.Locked=true
PA4.Signal=GPIO_Output
PA5.Locked=true
PA5.Mode=Full_Duplex_Master
PA5.Signal=SPI1_SCK
PA6.Locked=true
PA6.Mode=Full_Duplex_Master
PA6.Signal=SPI1_MISO
PA7.Locked=true
PA7.Mode=Full_Duplex_Master
PA7.Signal=SPI1_MOSI
PA8.GPIOParameters=GPIO_Label
PA8.GPIO_Label=RELAY_BATT_SIDE_ON
PA8.Locked=true
PA8.Signal=GPIO_Input
PA9.GPIOParameters=GPIO_Label
PA9.GPIO_Label=RELAY_ESC_SIDE_ON
PA9.Locked=true
PA9.Signal=GPIO_Input
PB0.GPIOParameters=PinState,GPIO_Label
PB0.GPIO_Label=STATUS_LED_R
PB0.Locked=true
PB0.PinState=GPIO_PIN_SET
PB0.Signal=GPIO_Output
PB1.GPIOParameters=PinState,GPIO_Label
PB1.GPIO_Label=STATUS_LED_B
PB1.Locked=true
PB1.PinState=GPIO_PIN_SET
PB1.Signal=GPIO_Output
PB11.GPIOParameters=PinState,GPIO_Label
PB11.GPIO_Label=PRECHARGE_EN
PB11.Locked=true
PB11.PinState=GPIO_PIN_RESET
PB11.Signal=GPIO_Output
PB13.GPIOParameters=GPIO_Label
PB13.GPIO_Label=AUX_IN
PB13.Locked=true
PB13.Signal=GPIO_Output
PB14.GPIOParameters=GPIO_Label
PB14.GPIO_Label=AUX_OUT
PB14.Locked=true
PB14.Signal=GPIO_Input
PB15.Locked=true
PB15.Mode=PWM Generation3 CH3N
PB15.Signal=TIM1_CH3N
PB2.GPIOParameters=PinState,GPIO_Label
PB2.GPIO_Label=STATUS_LED_G
PB2.Locked=true
PB2.PinState=GPIO_PIN_SET
PB2.Signal=GPIO_Output
PB3.Locked=true
PB3.Mode=Trace_Asynchronous_SW
PB3.Signal=SYS_JTDO-TRACESWO
PB6.Locked=true
PB6.Mode=Asynchronous
PB6.Signal=USART1_TX
PB7.Locked=true
PB7.Mode=Asynchronous
PB7.Signal=USART1_RX
PB9.Locked=true
PB9.Mode=I2C
PB9.Signal=I2C1_SDA
PF0-OSC_IN.Locked=true
PF0-OSC_IN.Mode=HSE-External-Oscillator
PF0-OSC_IN.Signal=RCC_OSC_IN
PF1-OSC_OUT.Locked=true
PF1-OSC_OUT.Mode=HSE-External-Oscillator
PF1-OSC_OUT.Signal=RCC_OSC_OUT
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
ProjectManager.CoupleFile=false
ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F302CBTx
ProjectManager.FirmwarePackage=STM32Cube FW_F3 V1.11.4
ProjectManager.FreePins=true
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=false
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=mvbms-test-24.ioc
ProjectManager.ProjectName=mvbms-test-24
ProjectManager.ProjectStructure=
ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=Makefile
ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN_Init-CAN-false-HAL-true,4-MX_I2C1_Init-I2C1-false-HAL-true,5-MX_SPI1_Init-SPI1-false-HAL-true,6-MX_TIM15_Init-TIM15-false-HAL-true,7-MX_USART1_UART_Init-USART1-false-HAL-true,8-MX_TIM1_Init-TIM1-false-HAL-true
RCC.ADC12outputFreq_Value=16000000
RCC.AHBFreq_Value=16000000
RCC.APB1Freq_Value=16000000
RCC.APB1TimFreq_Value=16000000
RCC.APB2Freq_Value=16000000
RCC.APB2TimFreq_Value=16000000
RCC.CortexFreq_Value=16000000
RCC.FCLKCortexFreq_Value=16000000
RCC.FamilyName=M
RCC.HCLKFreq_Value=16000000
RCC.HSEPLLFreq_Value=8000000
RCC.HSE_VALUE=8000000
RCC.HSIPLLFreq_Value=4000000
RCC.HSI_VALUE=8000000
RCC.I2C1Freq_Value=8000000
RCC.I2C2Freq_Value=8000000
RCC.IPParameters=ADC12outputFreq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSEPLLFreq_Value,HSE_VALUE,HSIPLLFreq_Value,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,LSE_VALUE,LSI_VALUE,MCOFreq_Value,PLLCLKFreq_Value,PLLMCOFreq_Value,PLLMUL,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSourceVirtual,TIM1Freq_Value,TIM2Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOOutput2Freq_Value
RCC.LSE_VALUE=32768
RCC.LSI_VALUE=40000
RCC.MCOFreq_Value=16000000
RCC.PLLCLKFreq_Value=16000000
RCC.PLLMCOFreq_Value=8000000
RCC.PLLMUL=RCC_PLL_MUL4
RCC.RTCFreq_Value=40000
RCC.RTCHSEDivFreq_Value=250000
RCC.SYSCLKFreq_VALUE=16000000
RCC.SYSCLKSourceVirtual=RCC_SYSCLKSOURCE_PLLCLK
RCC.TIM1Freq_Value=16000000
RCC.TIM2Freq_Value=16000000
RCC.USART1Freq_Value=16000000
RCC.USART2Freq_Value=16000000
RCC.USART3Freq_Value=16000000
RCC.USBFreq_Value=16000000
RCC.VCOOutput2Freq_Value=4000000
SH.S_TIM15_CH1.0=TIM15_CH1,PWM Generation1 CH1
SH.S_TIM15_CH1.ConfNb=1
SH.S_TIM15_CH2.0=TIM15_CH2,PWM Generation2 CH2
SH.S_TIM15_CH2.ConfNb=1
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_32
SPI1.CalculateBaudRate=500.0 KBits/s
SPI1.DataSize=SPI_DATASIZE_8BIT
SPI1.Direction=SPI_DIRECTION_2LINES
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler
SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
TIM1.Channel-PWM\ Generation3\ CH3N=TIM_CHANNEL_3
TIM1.IPParameters=Channel-PWM Generation3 CH3N
TIM15.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM15.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
TIM15.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2
USART1.IPParameters=VirtualMode-Asynchronous
USART1.VirtualMode-Asynchronous=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
board=custom